2 from __future__
import print_function
6 from sensor_msgs
import point_cloud2
7 from sensor_msgs.msg
import PointCloud2
8 from sensor_msgs.msg
import PointField
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)]
21 header.frame_id =
"map"
22 header.stamp = rospy.Time.now()
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
28 pc2 = point_cloud2.create_cloud(header, fields, points)
31 if __name__ ==
'__main__':
32 rospy.init_node(
'pc2_publisher')
33 pub = rospy.Publisher(
'points2', PointCloud2, queue_size=100)
37 while not rospy.is_shutdown():