-
Notifications
You must be signed in to change notification settings - Fork 466
/
send_point_cloud_2.py
47 lines (35 loc) · 1.2 KB
/
send_point_cloud_2.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
#!/usr/bin/env python
# This program publishes a pointcloud2 to test rviz rendering
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()