Skip to content

Commit

Permalink
added pointcoud2 example (ros#111)
Browse files Browse the repository at this point in the history
  • Loading branch information
flynneva authored Feb 17, 2021
1 parent e90266b commit 74cc182
Show file tree
Hide file tree
Showing 3 changed files with 53 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<node name="publish_pointcloud2" pkg="rospy_tutorials" type="publish_pointcloud2.py" output="screen"/>
</launch>

40 changes: 40 additions & 0 deletions rospy_tutorials/010_publish_pointcloud2/publish_pointcloud2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#!/usr/bin/env python
from __future__ import print_function

import rospy
import numpy as np
from sensor_msgs import point_cloud2
from sensor_msgs.msg import PointCloud2
from sensor_msgs.msg import PointField
from std_msgs.msg import Header

width = 100
height = 100

def publishPC2(count):
fields = [PointField('x', 0, PointField.FLOAT32, 1),
PointField('y', 4, PointField.FLOAT32, 1),
PointField('z', 8, PointField.FLOAT32, 1),
PointField('intensity', 12, PointField.FLOAT32, 1)]

header = Header()
header.frame_id = "map"
header.stamp = rospy.Time.now()

x, y = np.meshgrid(np.linspace(-2,2,width), np.linspace(-2,2,height))
z = 0.5 * np.sin(2*x - count/10.0) * np.sin(2*y)
points = np.array([x,y,z,z]).reshape(4,-1).T

pc2 = point_cloud2.create_cloud(header, fields, points)
pub.publish(pc2)

if __name__ == '__main__':
rospy.init_node('pc2_publisher')
pub = rospy.Publisher('points2', PointCloud2, queue_size=100)
rate = rospy.Rate(10)

count = 0
while not rospy.is_shutdown():
publishPC2(count)
count += 1
rate.sleep()
9 changes: 9 additions & 0 deletions rospy_tutorials/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,15 @@ install(FILES
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/009_advanced_publish
)

catkin_install_python(PROGRAMS
010_publish_pointcloud2/publish_pointcloud2.py
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/010_publish_pointcloud2
)
install(FILES
010_publish_pointcloud2/publish_pointcloud2.launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/010_publish_pointcloud2
)

if(CATKIN_ENABLE_TESTING)
find_package(rostest)
foreach(T
Expand Down

0 comments on commit 74cc182

Please sign in to comment.