publish_pointcloud2.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 from __future__ import print_function
3 
4 import rospy
5 import numpy as np
6 from sensor_msgs import point_cloud2
7 from sensor_msgs.msg import PointCloud2
8 from sensor_msgs.msg import PointField
9 from std_msgs.msg import Header
10 
11 width = 100
12 height = 100
13 
14 def publishPC2(count):
15  fields = [PointField('x', 0, PointField.FLOAT32, 1),
16  PointField('y', 4, PointField.FLOAT32, 1),
17  PointField('z', 8, PointField.FLOAT32, 1),
18  PointField('intensity', 12, PointField.FLOAT32, 1)]
19 
20  header = Header()
21  header.frame_id = "map"
22  header.stamp = rospy.Time.now()
23 
24  x, y = np.meshgrid(np.linspace(-2,2,width), np.linspace(-2,2,height))
25  z = 0.5 * np.sin(2*x - count/10.0) * np.sin(2*y)
26  points = np.array([x,y,z,z]).reshape(4,-1).T
27 
28  pc2 = point_cloud2.create_cloud(header, fields, points)
29  pub.publish(pc2)
30 
31 if __name__ == '__main__':
32  rospy.init_node('pc2_publisher')
33  pub = rospy.Publisher('points2', PointCloud2, queue_size=100)
34  rate = rospy.Rate(10)
35 
36  count = 0
37  while not rospy.is_shutdown():
38  publishPC2(count)
39  count += 1
40  rate.sleep()
msg
publish_pointcloud2.publishPC2
def publishPC2(count)
Definition: publish_pointcloud2.py:14


rospy_tutorials
Author(s): Ken Conley, Dirk Thomas
autogenerated on Sat Apr 12 2025 02:28:02