AS: adding first phase of orientation
This commit is contained in:
@@ -0,0 +1,33 @@
|
||||
#!/usr/bin/python3
|
||||
# EASY-INSTALL-ENTRY-SCRIPT: 'examples-rclpy-pointcloud-publisher==0.15.3','console_scripts','pointcloud_publisher'
|
||||
import re
|
||||
import sys
|
||||
|
||||
# for compatibility with easy_install; see #2198
|
||||
__requires__ = 'examples-rclpy-pointcloud-publisher==0.15.3'
|
||||
|
||||
try:
|
||||
from importlib.metadata import distribution
|
||||
except ImportError:
|
||||
try:
|
||||
from importlib_metadata import distribution
|
||||
except ImportError:
|
||||
from pkg_resources import load_entry_point
|
||||
|
||||
|
||||
def importlib_load_entry_point(spec, group, name):
|
||||
dist_name, _, _ = spec.partition('==')
|
||||
matches = (
|
||||
entry_point
|
||||
for entry_point in distribution(dist_name).entry_points
|
||||
if entry_point.group == group and entry_point.name == name
|
||||
)
|
||||
return next(matches).load()
|
||||
|
||||
|
||||
globals().setdefault('load_entry_point', importlib_load_entry_point)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
|
||||
sys.exit(load_entry_point('examples-rclpy-pointcloud-publisher==0.15.3', 'console_scripts', 'pointcloud_publisher')())
|
||||
@@ -0,0 +1,12 @@
|
||||
Metadata-Version: 2.1
|
||||
Name: examples-rclpy-pointcloud-publisher
|
||||
Version: 0.15.3
|
||||
Summary: Example on how to publish a Pointcloud2 message
|
||||
Home-page: UNKNOWN
|
||||
Maintainer: Aditya Pande, Shane Loretz
|
||||
Maintainer-email: aditya.pande@openrobotics.org, shane@openrobotics.org
|
||||
License: Apache 2.0
|
||||
Platform: UNKNOWN
|
||||
|
||||
UNKNOWN
|
||||
|
||||
@@ -0,0 +1,16 @@
|
||||
package.xml
|
||||
setup.cfg
|
||||
setup.py
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/PKG-INFO
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/SOURCES.txt
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/dependency_links.txt
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/entry_points.txt
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/requires.txt
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/top_level.txt
|
||||
../../../../../build/examples_rclpy_pointcloud_publisher/examples_rclpy_pointcloud_publisher.egg-info/zip-safe
|
||||
examples_rclpy_pointcloud_publisher/__init__.py
|
||||
examples_rclpy_pointcloud_publisher/pointcloud_publisher.py
|
||||
resource/examples_rclpy_pointcloud_publisher
|
||||
test/test_copyright.py
|
||||
test/test_flake8.py
|
||||
test/test_pep257.py
|
||||
@@ -0,0 +1 @@
|
||||
|
||||
@@ -0,0 +1,3 @@
|
||||
[console_scripts]
|
||||
pointcloud_publisher = examples_rclpy_pointcloud_publisher.pointcloud_publisher:main
|
||||
|
||||
@@ -0,0 +1 @@
|
||||
setuptools
|
||||
@@ -0,0 +1 @@
|
||||
examples_rclpy_pointcloud_publisher
|
||||
@@ -0,0 +1 @@
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,70 @@
|
||||
# Copyright 2020 Evan Flynn
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
import numpy as np
|
||||
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from sensor_msgs.msg import PointCloud2
|
||||
from sensor_msgs.msg import PointField
|
||||
from sensor_msgs_py import point_cloud2
|
||||
from std_msgs.msg import Header
|
||||
|
||||
|
||||
class PointCloudPublisher(Node):
|
||||
|
||||
rate = 30
|
||||
moving = True
|
||||
width = 100
|
||||
height = 100
|
||||
|
||||
header = Header()
|
||||
header.frame_id = 'map'
|
||||
|
||||
dtype = PointField.FLOAT32
|
||||
point_step = 16
|
||||
fields = [PointField(name='x', offset=0, datatype=dtype, count=1),
|
||||
PointField(name='y', offset=4, datatype=dtype, count=1),
|
||||
PointField(name='z', offset=8, datatype=dtype, count=1),
|
||||
PointField(name='intensity', offset=12, datatype=dtype, count=1)]
|
||||
|
||||
def __init__(self):
|
||||
super().__init__('pc_publisher')
|
||||
self.publisher_ = self.create_publisher(PointCloud2, 'test_cloud', 10)
|
||||
timer_period = 1 / self.rate
|
||||
self.timer = self.create_timer(timer_period, self.timer_callback)
|
||||
self.counter = 0
|
||||
|
||||
def timer_callback(self):
|
||||
self.header.stamp = self.get_clock().now().to_msg()
|
||||
x, y = np.meshgrid(np.linspace(-2, 2, self.width), np.linspace(-2, 2, self.height))
|
||||
z = 0.5 * np.sin(2*x-self.counter/10.0) * np.sin(2*y)
|
||||
points = np.array([x, y, z, z]).reshape(4, -1).T
|
||||
pc2_msg = point_cloud2.create_cloud(self.header, self.fields, points)
|
||||
self.publisher_.publish(pc2_msg)
|
||||
|
||||
if self.moving:
|
||||
self.counter += 1
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
pc_publisher = PointCloudPublisher()
|
||||
rclpy.spin(pc_publisher)
|
||||
pc_publisher.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
||||
Reference in New Issue
Block a user