Skip to content

Commit ac6b080

Browse files
committed
point_cloud_common: add test script and rviz config to verify correct behavior of "continuous transform" option
1 parent 73e977e commit ac6b080

File tree

2 files changed

+275
-0
lines changed

2 files changed

+275
-0
lines changed

src/test/point_cloud_test.py

Lines changed: 120 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
#!/usr/bin/env python
2+
3+
# This program publishes a pointcloud2 to test rviz rendering
4+
5+
from __future__ import print_function
6+
7+
import rospy
8+
import numpy as np
9+
from sensor_msgs import point_cloud2
10+
from sensor_msgs.msg import PointCloud2
11+
from sensor_msgs.msg import PointField
12+
from std_msgs.msg import Header
13+
14+
import math
15+
import time
16+
from geometry_msgs.msg import TransformStamped
17+
from tf2_ros.transform_broadcaster import TransformBroadcaster
18+
from tf.transformations import quaternion_from_euler
19+
from visualization_msgs.msg import Marker
20+
21+
RATE = 30
22+
width = 100
23+
height = 100
24+
25+
26+
def generate_point_cloud():
27+
fields = [
28+
PointField("x", 0, PointField.FLOAT32, 1),
29+
PointField("y", 4, PointField.FLOAT32, 1),
30+
PointField("z", 8, PointField.FLOAT32, 1),
31+
PointField("intensity", 12, PointField.FLOAT32, 1),
32+
]
33+
34+
header = Header()
35+
header.frame_id = "map"
36+
header.stamp = rospy.Time.now()
37+
38+
x, y = np.meshgrid(np.linspace(-2, 2, width), np.linspace(-2, 2, height))
39+
z = 0.5 * np.sin(2 * x) * np.sin(3 * y)
40+
points = np.array([x, y, z, z]).reshape(4, -1).T
41+
42+
return point_cloud2.create_cloud(header, fields, points)
43+
44+
45+
def draw_eight(elapsed_time, full_cycle_duration=10, scale=10):
46+
# lemniscate of Gerono
47+
progress = (elapsed_time % full_cycle_duration) / full_cycle_duration
48+
t = -0.5 * math.pi + progress * (2 * math.pi)
49+
x = math.cos(t) * scale
50+
y = math.sin(t) * math.cos(t) * scale
51+
dx_dt = -math.sin(t)
52+
dy_dt = math.cos(t) * math.cos(t) - math.sin(t) * math.sin(t)
53+
yaw = math.atan2(dy_dt, dx_dt)
54+
return x, y, yaw
55+
56+
57+
def display_dummy_robot(stamp):
58+
marker = Marker()
59+
marker.header.frame_id = "base_link"
60+
marker.header.stamp = stamp
61+
marker.ns = "robot"
62+
marker.id = 0
63+
marker.type = Marker.CUBE
64+
marker.action = Marker.ADD
65+
marker.pose.position.x = 0
66+
marker.pose.position.y = 0
67+
marker.pose.position.z = 0
68+
marker.pose.orientation.x = 0.0
69+
marker.pose.orientation.y = 0.0
70+
marker.pose.orientation.z = 0.0
71+
marker.pose.orientation.w = 1.0
72+
marker.scale.x = 1
73+
marker.scale.y = 1
74+
marker.scale.z = 1
75+
marker.color.a = 1.0
76+
marker.color.r = 0.0
77+
marker.color.g = 1.0
78+
marker.color.b = 0.0
79+
vis_pub.publish(marker)
80+
81+
82+
if __name__ == "__main__":
83+
rospy.init_node("point_cloud_test")
84+
85+
tf_broadcaster = TransformBroadcaster()
86+
87+
vis_pub = rospy.Publisher("robot/marker", Marker, queue_size=5)
88+
pc_pub = rospy.Publisher("points2", PointCloud2, queue_size=5)
89+
pc = generate_point_cloud()
90+
91+
i = 0
92+
rate = rospy.Rate(RATE)
93+
start = rospy.Time.now()
94+
while not rospy.is_shutdown():
95+
now = rospy.Time.now()
96+
97+
if i % RATE == 0:
98+
# publish just once per second
99+
pc.header.stamp = now
100+
pc_pub.publish(pc)
101+
i += 1
102+
103+
robot_x, robot_y, robot_yaw = draw_eight((now - start).to_sec())
104+
q = quaternion_from_euler(0, 0, robot_yaw)
105+
106+
tf = TransformStamped()
107+
tf.header.frame_id = "map"
108+
tf.header.stamp = now
109+
tf.child_frame_id = "base_link"
110+
tf.transform.translation.x = robot_x
111+
tf.transform.translation.y = robot_y
112+
tf.transform.rotation.x = q[0]
113+
tf.transform.rotation.y = q[1]
114+
tf.transform.rotation.z = q[2]
115+
tf.transform.rotation.w = q[3]
116+
tf_broadcaster.sendTransform(tf)
117+
118+
display_dummy_robot(now)
119+
120+
rate.sleep()

src/test/point_cloud_test.rviz

Lines changed: 155 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,155 @@
1+
Panels:
2+
- Class: rviz/Displays
3+
Help Height: 78
4+
Name: Displays
5+
Property Tree Widget:
6+
Expanded:
7+
- /Global Options1
8+
Splitter Ratio: 0.5
9+
Tree Height: 818
10+
- Class: rviz/Selection
11+
Name: Selection
12+
- Class: rviz/Tool Properties
13+
Expanded:
14+
- /2D Pose Estimate1
15+
- /2D Nav Goal1
16+
- /Publish Point1
17+
Name: Tool Properties
18+
Splitter Ratio: 0.5886790156364441
19+
- Class: rviz/Views
20+
Expanded:
21+
- /Current View1
22+
Name: Views
23+
Splitter Ratio: 0.5
24+
- Class: rviz/Time
25+
Experimental: false
26+
Name: Time
27+
SyncMode: 0
28+
SyncSource: PointCloud2
29+
Preferences:
30+
PromptSaveOnExit: true
31+
Toolbars:
32+
toolButtonStyle: 2
33+
Visualization Manager:
34+
Class: ""
35+
Displays:
36+
- Alpha: 0.5
37+
Cell Size: 1
38+
Class: rviz/Grid
39+
Color: 160; 160; 164
40+
Enabled: true
41+
Line Style:
42+
Line Width: 0.029999999329447746
43+
Value: Lines
44+
Name: Grid
45+
Normal Cell Count: 0
46+
Offset:
47+
X: 0
48+
Y: 0
49+
Z: 0
50+
Plane: XY
51+
Plane Cell Count: 10
52+
Reference Frame: map
53+
Value: true
54+
- Alpha: 1
55+
Autocompute Intensity Bounds: true
56+
Autocompute Value Bounds:
57+
Max Value: 10
58+
Min Value: -10
59+
Value: true
60+
Axis: Z
61+
Channel Name: intensity
62+
Class: rviz/PointCloud2
63+
Color: 255; 255; 255
64+
Color Transformer: Intensity
65+
Decay Time: 0
66+
Enabled: true
67+
Invert Rainbow: false
68+
Max Color: 255; 255; 255
69+
Min Color: 0; 0; 0
70+
Name: PointCloud2
71+
Position Transformer: XYZ
72+
Queue Size: 10
73+
Selectable: true
74+
Size (Pixels): 3
75+
Size (m): 0.05000000074505806
76+
Style: Flat Squares
77+
Topic: /points2
78+
Unreliable: false
79+
Use Fixed Frame: true
80+
Use rainbow: true
81+
Value: true
82+
- Class: rviz/Marker
83+
Enabled: true
84+
Marker Topic: /robot/marker
85+
Name: Marker
86+
Namespaces:
87+
robot: true
88+
Queue Size: 100
89+
Value: true
90+
Enabled: true
91+
Global Options:
92+
Background Color: 48; 48; 48
93+
Default Light: true
94+
Fixed Frame: map
95+
Frame Rate: 30
96+
Name: root
97+
Tools:
98+
- Class: rviz/Interact
99+
Hide Inactive Objects: true
100+
- Class: rviz/MoveCamera
101+
- Class: rviz/Select
102+
- Class: rviz/FocusCamera
103+
- Class: rviz/Measure
104+
- Class: rviz/SetInitialPose
105+
Theta std deviation: 0.2617993950843811
106+
Topic: /initialpose
107+
X std deviation: 0.5
108+
Y std deviation: 0.5
109+
- Class: rviz/SetGoal
110+
Topic: /move_base_simple/goal
111+
- Class: rviz/PublishPoint
112+
Single click: true
113+
Topic: /clicked_point
114+
Value: true
115+
Views:
116+
Current:
117+
Class: rviz/Orbit
118+
Distance: 30.52842903137207
119+
Enable Stereo Rendering:
120+
Stereo Eye Separation: 0.05999999865889549
121+
Stereo Focal Distance: 1
122+
Swap Stereo Eyes: false
123+
Value: false
124+
Field of View: 0.7853981852531433
125+
Focal Point:
126+
X: 0
127+
Y: 0
128+
Z: 0
129+
Focal Shape Fixed Size: true
130+
Focal Shape Size: 0.05000000074505806
131+
Invert Z Axis: false
132+
Name: Current View
133+
Near Clip Distance: 0.009999999776482582
134+
Pitch: 0.6153981685638428
135+
Target Frame: <Fixed Frame>
136+
Yaw: 1.025397777557373
137+
Saved: ~
138+
Window Geometry:
139+
Displays:
140+
collapsed: false
141+
Height: 1115
142+
Hide Left Dock: false
143+
Hide Right Dock: false
144+
QMainWindow State: 000000ff00000000fd000000040000000000000156000003bdfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003bd000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003bdfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003bd000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000050f000003bd00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
145+
Selection:
146+
collapsed: false
147+
Time:
148+
collapsed: false
149+
Tool Properties:
150+
collapsed: false
151+
Views:
152+
collapsed: false
153+
Width: 1920
154+
X: 0
155+
Y: 0

0 commit comments

Comments
 (0)