-
Notifications
You must be signed in to change notification settings - Fork 570
/
Copy pathlidar3d_assemble.launch.py
226 lines (189 loc) · 8.2 KB
/
lidar3d_assemble.launch.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
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
# Description:
# In this example, we will record ALL lidar scans. An IMU or low latency odometry is required for this example.
#
# Example:
# Launch your lidar sensor:
# $ ros2 launch velodyne_driver velodyne_driver_node-VLP16-launch.py
# $ ros2 launch velodyne_pointcloud velodyne_transform_node-VLP16-launch.py
#
# Launch your IMU sensor, make sure TF between lidar/base frame and imu is already calibrated.
# In this example, we assume the imu topic has
# already the orientation estimated, it not, you can launch
# imu_filter_madgwick_node (with use_mag:=false publish_tf:=false)
# and set imu_topic to output topic of the filter.
#
# If a camera is used, make sure TF between lidar/base frame and camera is
# already calibrated. To provide image data to this example, you should use
# rtabmap_sync's rgbd_sync or stereo_sync node.
#
# Launch the example by adjusting the lidar topic, imu topic and base frame:
# $ ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:=/velodyne_points imu_topic:=/imu/data frame_id:=velodyne
from launch import LaunchDescription, LaunchContext
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def launch_setup(context: LaunchContext, *args, **kwargs):
frame_id = LaunchConfiguration('frame_id')
fixed_frame_from_imu = False
fixed_frame_id = LaunchConfiguration('fixed_frame_id').perform(context)
if not fixed_frame_id:
fixed_frame_from_imu = True
fixed_frame_id = frame_id.perform(context) + "_stabilized"
imu_topic = LaunchConfiguration('imu_topic')
rgbd_image_topic = LaunchConfiguration('rgbd_image_topic')
rgbd_image_used = rgbd_image_topic.perform(context) != ''
lidar_topic = LaunchConfiguration('lidar_topic')
lidar_topic_value = lidar_topic.perform(context)
lidar_topic_deskewed = lidar_topic_value + "/deskewed"
voxel_size = LaunchConfiguration('voxel_size')
voxel_size_value = float(voxel_size.perform(context))
use_sim_time = LaunchConfiguration('use_sim_time')
localization = LaunchConfiguration('localization').perform(context)
localization = localization == 'true' or localization == 'True'
# Rule of thumb:
max_correspondence_distance = voxel_size_value * 10.0
shared_parameters = {
'use_sim_time': use_sim_time,
'frame_id': frame_id,
'qos': LaunchConfiguration('qos'),
'approx_sync': rgbd_image_used,
'wait_for_transform': 0.2,
# RTAB-Map's internal parameters are strings:
'Icp/PointToPlane': 'true',
'Icp/Iterations': '10',
'Icp/VoxelSize': str(voxel_size_value),
'Icp/Epsilon': '0.001',
'Icp/PointToPlaneK': '20',
'Icp/PointToPlaneRadius': '0',
'Icp/MaxTranslation': '3',
'Icp/MaxCorrespondenceDistance': str(max_correspondence_distance),
'Icp/Strategy': '1',
'Icp/OutlierRatio': '0.7',
}
icp_odometry_parameters = {
'expected_update_rate': 15.0,
'wait_imu_to_init': True,
'odom_frame_id': 'icp_odom',
'guess_frame_id': fixed_frame_id,
# RTAB-Map's internal parameters are strings:
'Odom/ScanKeyFrameThr': '0.4',
'OdomF2M/ScanSubtractRadius': str(voxel_size_value),
'OdomF2M/ScanMaxSize': '15000',
'OdomF2M/BundleAdjustment': 'false',
'Icp/CorrespondenceRatio': '0.01'
}
rtabmap_parameters = {
'subscribe_depth': False,
'subscribe_rgb': False,
'subscribe_odom_info': True,
'subscribe_scan_cloud': True,
'odom_sensor_sync': True, # This will adjust camera position based on difference between lidar and camera stamps.
# RTAB-Map's internal parameters are strings:
'Rtabmap/DetectionRate': '0', # indirectly set to 1 Hz by the assembling time below (1s)
'RGBD/ProximityMaxGraphDepth': '0',
'RGBD/ProximityPathMaxNeighbors': '1',
'RGBD/AngularUpdate': '0.05',
'RGBD/LinearUpdate': '0.05',
'RGBD/CreateOccupancyGrid': 'false',
'Mem/NotLinkedNodesKept': 'false',
'Mem/STMSize': '30',
'Reg/Strategy': '1',
'Icp/CorrespondenceRatio': '0.2'
}
remappings = [('imu', imu_topic),
('odom', 'icp_odom')]
if rgbd_image_used:
remappings.append(('rgbd_image', LaunchConfiguration('rgbd_image_topic')))
arguments = []
if localization:
rtabmap_parameters['Mem/IncrementalMemory'] = 'False'
rtabmap_parameters['Mem/InitWMWithAllNodes'] = 'True'
else:
arguments.append('-d') # This will delete the previous database (~/.ros/rtabmap.db)
nodes = [
# Lidar deskewing
Node(
package='rtabmap_util', executable='lidar_deskewing', output='screen',
parameters=[{
'use_sim_time': use_sim_time,
'fixed_frame_id': fixed_frame_id,
'wait_for_transform': 0.2}],
remappings=[
('input_cloud', lidar_topic)
]),
# Lidar odometry
Node(
package='rtabmap_odom', executable='icp_odometry', output='screen',
parameters=[shared_parameters, icp_odometry_parameters],
remappings=remappings + [('scan_cloud', lidar_topic_deskewed)]),
# Assemble deskewed scans based on icp odometry
Node(
package='rtabmap_util', executable='point_cloud_assembler', output='screen',
parameters=[{
'use_sim_time': use_sim_time,
'assembling_time': LaunchConfiguration('assembling_time'),
'fixed_frame_id': ""}], # This will make the node subscribing to icp odometry topic "odom"
remappings=[('cloud', lidar_topic_deskewed),
('odom', 'icp_odom')]),
# Update the map
Node(
package='rtabmap_slam', executable='rtabmap', output='screen',
parameters=[shared_parameters, rtabmap_parameters,
{'subscribe_rgbd': rgbd_image_used,
'topic_queue_size': 30,
'sync_queue_size': 20,}],
remappings=remappings + [('scan_cloud', 'assembled_cloud')],
arguments=arguments),
# Just for visualization
Node(
package='rtabmap_viz', executable='rtabmap_viz', output='screen',
parameters=[shared_parameters, rtabmap_parameters],
remappings=remappings + [('scan_cloud', 'odom_filtered_input_scan')])
]
if fixed_frame_from_imu:
# Create a stabilized base frame based on imu for lidar deskewing
nodes.append(
Node(
package='rtabmap_util', executable='imu_to_tf', output='screen',
parameters=[{
'use_sim_time': use_sim_time,
'fixed_frame_id': fixed_frame_id,
'base_frame_id': frame_id,
'wait_for_transform_duration': 0.001}],
remappings=[('imu/data', imu_topic)]))
return nodes
def generate_launch_description():
return LaunchDescription([
# Launch arguments
DeclareLaunchArgument(
'use_sim_time', default_value='false',
description='Use simulated clock.'),
DeclareLaunchArgument(
'frame_id', default_value='velodyne',
description='Base frame of the robot.'),
DeclareLaunchArgument(
'fixed_frame_id', default_value='',
description='Fixed frame used for lidar deskewing. If not set, we will generate one from IMU.'),
DeclareLaunchArgument(
'localization', default_value='false',
description='Localization mode.'),
DeclareLaunchArgument(
'lidar_topic', default_value='/velodyne_points',
description='Name of the lidar PointCloud2 topic.'),
DeclareLaunchArgument(
'imu_topic', default_value='/imu/data',
description='Name of an IMU topic.'),
DeclareLaunchArgument(
'rgbd_image_topic', default_value='',
description='RGBD image topic (ignored if empty). Would be the output of a rtabmap_sync\'s rgbd_sync, stereo_sync or rgb_sync node.'),
DeclareLaunchArgument(
'voxel_size', default_value='0.1',
description='Voxel size (m) of the downsampled lidar point cloud. For indoor, set it between 0.1 and 0.3. For outdoor, set it to 0.5 or over.'),
DeclareLaunchArgument(
'assembling_time', default_value='1.0',
description='How much time (sec) we assemble lidar scans before sending them to mapping node.'),
DeclareLaunchArgument(
'qos', default_value='1',
description='Quality of Service: 0=system default, 1=reliable, 2=best effort.'),
OpaqueFunction(function=launch_setup),
])