-
Notifications
You must be signed in to change notification settings - Fork 198
/
dynamic_robot_localization_system.launch
executable file
·268 lines (247 loc) · 21.4 KB
/
dynamic_robot_localization_system.launch
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
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- ======================================================= arguments ==================================================== -->
<!-- initial pose topics -->
<arg name="pose_topic" default="initial_pose" />
<arg name="pose_stamped_topic" default="initial_pose_stamped" />
<arg name="pose_with_covariance_stamped_topic" default="/initialpose" /> <!-- rviz topic -->
<arg name="pose_with_covariance_stamped_publish_topic" default="localization_pose_with_covariance" /> <!-- rviz topic -->
<!-- published pose -->
<arg name="pose_stamped_publish_topic" default="localization_pose" />
<!-- frame ids -->
<arg name="map_frame_id" default="map" />
<arg name="odom_frame_id" default="odom" />
<arg name="base_link_frame_id" default="base_footprint" />
<arg name="sensor_frame_id" default="hokuyo_front_laser_link" />
<!-- main configurations -->
<arg name="use_ukf_filtering" default="false" />
<arg name="nodes_namespace" default="dynamic_robot_localization" />
<arg name="nodes_respawn" default="true" />
<arg name="drl_localization_node_name" default="drl_localization_node" />
<arg name="pcl_verbosity_level" default="ERROR" /> <!-- VERBOSE | DEBUG | INFO | WARN | ERROR | ALWAYS || ALWAYS -> no console output -->
<arg name="ros_verbosity_level" default="INFO" /> <!-- DEBUG | INFO | WARN | ERROR | FATAL -->
<arg name="yaml_configuration_filters_filename" default="$(find dynamic_robot_localization)/yaml/configs/filters/filters_large_map_2d.yaml" />
<arg name="yaml_configuration_pose_estimation_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_estimation/initial_pose_estimation_large_map_2d.yaml" />
<arg name="yaml_configuration_tracking_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_tracking/cluttered_environments_dynamic_large_map_2d.yaml" />
<arg name="yaml_configuration_recovery_filename" default="$(find dynamic_robot_localization)/yaml/configs/pose_recovery/recovery_2d.yaml" />
<arg name="yaml_configuration_covariance_filename" default="$(find dynamic_robot_localization)/yaml/configs/covariance_estimation/covariance_estimation.yaml" if="$(arg use_ukf_filtering)" />
<arg name="yaml_configuration_covariance_filename" default="$(find dynamic_robot_localization)/yaml/configs/empty.yaml" unless="$(arg use_ukf_filtering)" />
<!-- reference map data -->
<arg name="reference_pointcloud_filename" default="" />
<arg name="reference_pointcloud_preprocessed_save_filename" default="" />
<arg name="reference_pointcloud_available" default="true" />
<arg name="reference_pointcloud_type_3d" default="false" />
<arg name="reference_pointcloud_type" default="2D" unless="$(arg reference_pointcloud_type_3d)"/>
<arg name="reference_pointcloud_type" default="3D" if="$(arg reference_pointcloud_type_3d)" />
<arg name="reference_pointcloud_update_mode" default="NoIntegration" if="$(arg reference_pointcloud_available)"/> <!-- NoIntegration | FullIntegration | InliersIntegration | OutliersIntegration -->
<arg name="reference_pointcloud_update_mode" default="FullIntegration" unless="$(arg reference_pointcloud_available)"/>
<arg name="reference_pointcloud_keypoints_filename" default="" />
<arg name="reference_pointcloud_keypoints_save_filename" default="" />
<arg name="reference_pointcloud_descriptors_filename" default="" />
<arg name="reference_pointcloud_descriptors_save_filename" default="" />
<arg name="reference_costmap_topic" default="" if="$(arg reference_pointcloud_type_3d)" />
<arg name="reference_costmap_topic" default="/map" unless="$(arg reference_pointcloud_type_3d)" />
<arg name="reference_costmap_topic_updated" default="/map_updated" />
<arg name="reference_pointcloud_topic" default="reference_pointcloud_updated" if="$(arg reference_pointcloud_type_3d)" /> <!-- OctoMap is configured to use topic 'reference_pointcloud_update' -->
<arg name="reference_pointcloud_topic" default="" unless="$(arg reference_pointcloud_type_3d)" />
<!-- sensor data from point cloud topic -->
<arg name="ambient_pointcloud_topic" default="ambient_pointcloud" />
<arg name="ambient_pointcloud_topic_disabled_on_startup" default="false" />
<arg name="imu_topic" default="imu" />
<!-- initial pose setup -->
<arg name="robot_initial_pose_in_base_to_map" default="false" /> <!-- recommendation: use false to allow direct publish of tf between odom -> map -->
<arg name="robot_initial_pose_available" default="false" />
<arg name="robot_initial_x" default="0.0" />
<arg name="robot_initial_y" default="0.0" />
<arg name="robot_initial_z" default="0.0" />
<arg name="robot_initial_roll" default="0.0" />
<arg name="robot_initial_pitch" default="0.0" />
<arg name="robot_initial_yaw" default="0.0" />
<!-- laser scan assembler -->
<arg name="use_laser_assembler" default="true" />
<arg name="assemble_lasers_on_map_frame" default="false" /> <!-- if false -> assembles lasers on odom frame -->
<arg name="laser_assembly_frame" default="$(arg map_frame_id)" if="$(arg assemble_lasers_on_map_frame)" />
<arg name="laser_assembly_frame" default="$(arg odom_frame_id)" unless="$(arg assemble_lasers_on_map_frame)" />
<arg name="laser_assembly_motion_estimation_source_frame_id" default="" />
<arg name="laser_assembly_motion_estimation_target_frame_id" default="" />
<arg name="laser_scan_topics" default="/tilt_scan+/base_scan" />
<arg name="min_range_cutoff_percentage_offset" default="2.00" />
<arg name="max_range_cutoff_percentage_offset" default="0.95" />
<arg name="laser_assembler_remove_invalid_measurements" default="true" />
<arg name="number_of_tf_queries_for_spherical_interpolation" default="4" />
<arg name="number_of_scans_to_assemble_per_cloud" default="2" />
<arg name="timeout_for_cloud_assembly" default="0.5" />
<arg name="dynamic_update_of_assembly_configuration_from_twist_topic" default="" />
<arg name="dynamic_update_of_assembly_configuration_from_odometry_topic" default="odom" />
<arg name="dynamic_update_of_assembly_configuration_from_imu_topic" default="" />
<arg name="min_number_of_scans_to_assemble_per_cloud" default="2" />
<arg name="max_number_of_scans_to_assemble_per_cloud" default="20" />
<arg name="min_timeout_seconds_for_cloud_assembly" default="0.15" />
<arg name="max_timeout_seconds_for_cloud_assembly" default="1.1" />
<arg name="max_linear_velocity" default="0.025" /> <!-- when the linear velocity of the robot is equal or greater than this value, the number of scans to join and assembly timeout will be set to their minimum values specified above -->
<arg name="max_angular_velocity" default="0.174532925" /> <!-- when the angular velocity of the robot is equal or greater than this value, the number of scans to join and assembly timeout will be set to their minimum values specified above -->
<!-- tf configurations -->
<arg name="publish_tf_map_odom" default="true" />
<arg name="publish_initial_pose" default="true" />
<arg name="publish_pose_tf_rate" default="-10.0" />
<arg name="tf_lookup_timeout" default="0.1" />
<arg name="publish_last_pose_tf_timeout_seconds" default="3.0" /> <!-- set to negative value for publishing a tf only when drl estimates a new pose -->
<arg name="invert_tf_transform" default="false" />
<arg name="invert_tf_hierarchy" default="false" />
<arg name="transform_pose_to_map_frame_id" default="true" />
<!-- map update -->
<arg name="use_octomap_for_dynamic_map_update" default="false" />
<arg name="use_octomap_only_to_build_occupancy_grid" default="false" />
<arg name="octomap_pointcloud_topic" default="aligned_pointcloud" /> <!-- ambient_pointcloud | aligned_pointcloud | aligned_pointcloud_outliers | aligned_pointcloud_inliers -->
<arg name="octomap_file" default="" />
<arg name="octomap_sensor_frame_id" default="$(arg sensor_frame_id)" />
<arg name="octomap_resolution" default="0.025" />
<arg name="octomap_minimum_amount_of_time_between_ros_msg_publishing" default="5.0" />
<arg name="octomap_minimum_number_of_integrations_before_ros_msg_publishing" default="10" />
<arg name="octomap_override_sensor_z" default="false" if="$(arg reference_pointcloud_type_3d)" />
<arg name="octomap_override_sensor_z" default="true" unless="$(arg reference_pointcloud_type_3d)" />
<arg name="octomap_override_sensor_z_value" default="0.0" />
<arg name="octomap_cloud_out_topic" default="reference_pointcloud_updated" />
<arg name="initial_2d_map_file" default="" />
<!-- ==================================================== localization system ============================================= -->
<!-- <node pkg="dynamic_robot_localization" type="drl_localization_node" name="$(arg drl_localization_node_name)" respawn="$(arg nodes_respawn)" ns="$(arg nodes_namespace)" clear_params="true" output="screen" launch-prefix="gdbserver localhost:1337" > -->
<node pkg="dynamic_robot_localization" type="drl_localization_node" name="$(arg drl_localization_node_name)" respawn="$(arg nodes_respawn)" ns="$(arg nodes_namespace)" clear_params="true" output="screen" >
<param name="pcl_verbosity_level" type="str" value="$(arg pcl_verbosity_level)" />
<param name="ros_verbosity_level" type="str" value="$(arg ros_verbosity_level)" />
<param name="message_management/tf_timeout" type="double" value="$(arg tf_lookup_timeout)" />
<param name="frame_ids/map_frame_id" type="str" value="$(arg map_frame_id)" />
<param name="frame_ids/odom_frame_id" type="str" value="$(arg odom_frame_id)" />
<param name="frame_ids/base_link_frame_id" type="str" value="$(arg base_link_frame_id)" />
<param name="frame_ids/sensor_frame_id" type="str" value="$(arg sensor_frame_id)" />
<param name="initial_pose/robot_initial_pose_in_base_to_map" type="bool" value="$(arg robot_initial_pose_in_base_to_map)" />
<param name="initial_pose/robot_initial_pose_available" type="bool" value="$(arg robot_initial_pose_available)" />
<param name="initial_pose/position/x" type="double" value="$(arg robot_initial_x)" />
<param name="initial_pose/position/y" type="double" value="$(arg robot_initial_y)" />
<param name="initial_pose/position/z" type="double" value="$(arg robot_initial_z)" />
<param name="initial_pose/orientation_rpy/roll" type="double" value="$(arg robot_initial_roll)" />
<param name="initial_pose/orientation_rpy/pitch" type="double" value="$(arg robot_initial_pitch)" />
<param name="initial_pose/orientation_rpy/yaw" type="double" value="$(arg robot_initial_yaw)" />
<param name="subscribe_topic_names/pose_topic" type="str" value="$(arg pose_topic)" />
<param name="subscribe_topic_names/pose_stamped_topic" type="str" value="$(arg pose_stamped_topic)" />
<param name="subscribe_topic_names/pose_with_covariance_stamped_topic" type="str" value="$(arg pose_with_covariance_stamped_topic)" />
<param name="subscribe_topic_names/ambient_pointcloud_topic" type="str" value="$(arg ambient_pointcloud_topic)" />
<param name="subscribe_topic_names/ambient_pointcloud_topic_disabled_on_startup" type="bool" value="$(arg ambient_pointcloud_topic_disabled_on_startup)" />
<param name="subscribe_topic_names/reference_costmap_topic" type="str" value="$(arg reference_costmap_topic)" />
<param name="subscribe_topic_names/reference_pointcloud_topic" type="str" value="$(arg reference_pointcloud_topic)" />
<param name="publish_topic_names/pose_with_covariance_stamped_publish_topic" type="str" value="$(arg pose_with_covariance_stamped_publish_topic)" />
<param name="publish_topic_names/pose_stamped_publish_topic" type="str" value="$(arg pose_stamped_publish_topic)" />
<param name="reference_pointclouds/reference_pointcloud_filename" type="str" value="$(arg reference_pointcloud_filename)" />
<param name="reference_pointclouds/reference_pointcloud_preprocessed_save_filename" type="str" value="$(arg reference_pointcloud_preprocessed_save_filename)" />
<param name="reference_pointclouds/reference_pointcloud_type" type="str" value="$(arg reference_pointcloud_type)" />
<param name="reference_pointclouds/reference_pointcloud_available" type="bool" value="$(arg reference_pointcloud_available)" />
<param name="reference_pointclouds/reference_pointcloud_update_mode" type="str" value="$(arg reference_pointcloud_update_mode)" />
<param name="keypoint_detectors/reference_pointcloud/reference_pointcloud_keypoints_filename" type="str" value="$(arg reference_pointcloud_keypoints_filename)" />
<param name="keypoint_detectors/reference_pointcloud/reference_pointcloud_keypoints_save_filename" type="str" value="$(arg reference_pointcloud_keypoints_save_filename)" />
<param name="initial_pose_estimators_matchers/feature_matchers/reference_pointcloud_descriptors_filename" type="str" value="$(arg reference_pointcloud_descriptors_filename)" />
<param name="initial_pose_estimators_matchers/feature_matchers/reference_pointcloud_descriptors_save_filename" type="str" value="$(arg reference_pointcloud_descriptors_save_filename)" />
<rosparam command="load" file="$(arg yaml_configuration_filters_filename)" subst_value="true" />
<rosparam command="load" file="$(arg yaml_configuration_pose_estimation_filename)" subst_value="true" />
<rosparam command="load" file="$(arg yaml_configuration_recovery_filename)" subst_value="true" />
<rosparam command="load" file="$(arg yaml_configuration_tracking_filename)" subst_value="true" />
<rosparam command="load" file="$(arg yaml_configuration_covariance_filename)" subst_value="true" />
</node>
<include file="$(find dynamic_robot_localization)/launch/ukf.launch" ns="$(arg nodes_namespace)" if="$(arg use_ukf_filtering)" >
<arg name="planar_pose_estimation" default="false" if="$(arg reference_pointcloud_type_3d)" />
<arg name="planar_pose_estimation" default="true" unless="$(arg reference_pointcloud_type_3d)" />
<arg name="tracking_state_reset_topic" default="initial_pose_with_covariance" />
<arg name="sensor_timeout" default="$(arg publish_last_pose_tf_timeout_seconds)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="odometry_topic" default="$(arg dynamic_update_of_assembly_configuration_from_odometry_topic)" />
<arg name="imu_topic" default="$(arg imu_topic)" />
<arg name="nodes_respawn" default="$(arg nodes_respawn)" />
</include>
<!-- map to odom publisher -->
<include file="$(find pose_to_tf_publisher)/launch/pose_to_tf_publisher.launch" if="$(arg publish_tf_map_odom)" >
<arg name="publish_rate" default="$(arg publish_pose_tf_rate)" />
<arg name="tf_lookup_timeout" default="1.5" />
<arg name="publish_last_pose_tf_timeout_seconds" default="$(arg publish_last_pose_tf_timeout_seconds)" />
<arg name="pose_with_covariance_stamped_topic" default="$(arg pose_with_covariance_stamped_topic)" /> <!-- rviz topic -->
<arg name="pose_stamped_topic" default="$(arg pose_stamped_publish_topic)" />
<arg name="odometry_topic" default="" />
<arg name="map_frame_id" default="$(arg map_frame_id)_drl" if="$(arg use_ukf_filtering)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" unless="$(arg use_ukf_filtering)" />
<arg name="odom_frame_id" default="$(arg odom_frame_id)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="publish_initial_pose" default="$(arg publish_initial_pose)" />
<arg name="initial_pose_in_base_to_map" default="$(arg robot_initial_pose_in_base_to_map)" />
<arg name="initial_x" default="$(arg robot_initial_x)" />
<arg name="initial_y" default="$(arg robot_initial_y)" />
<arg name="initial_z" default="$(arg robot_initial_z)" />
<arg name="initial_roll" default="$(arg robot_initial_roll)" />
<arg name="initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="invert_tf_transform" default="true" if="$(arg use_ukf_filtering)" />
<arg name="invert_tf_transform" default="$(arg invert_tf_transform)" unless="$(arg use_ukf_filtering)" />
<arg name="invert_tf_hierarchy" default="true" if="$(arg use_ukf_filtering)" />
<arg name="invert_tf_hierarchy" default="$(arg invert_tf_hierarchy)" unless="$(arg use_ukf_filtering)" />
<arg name="transform_pose_to_map_frame_id" default="false" if="$(arg use_ukf_filtering)" />
<arg name="transform_pose_to_map_frame_id" default="$(arg transform_pose_to_map_frame_id)" unless="$(arg use_ukf_filtering)" />
<arg name="parameters_namespace" default="dynamic_robot_localization" />
<arg name="nodes_respawn" default="$(arg nodes_respawn)" />
</include>
<!-- laser assembler -->
<include file="$(find laserscan_to_pointcloud)/launch/laserscan_to_pointcloud_assembler.launch" ns="$(arg nodes_namespace)" if="$(arg use_laser_assembler)" >
<arg name="laser_scan_topics" default="$(arg laser_scan_topics)" />
<arg name="number_of_tf_queries_for_spherical_interpolation" default="$(arg number_of_tf_queries_for_spherical_interpolation)" />
<arg name="number_of_scans_to_assemble_per_cloud" default="$(arg number_of_scans_to_assemble_per_cloud)" />
<arg name="timeout_for_cloud_assembly" default="$(arg timeout_for_cloud_assembly)" />
<arg name="remove_invalid_measurements" default="$(arg laser_assembler_remove_invalid_measurements)" />
<arg name="dynamic_update_of_assembly_configuration_from_twist_topic" default="$(arg dynamic_update_of_assembly_configuration_from_twist_topic)" />
<arg name="dynamic_update_of_assembly_configuration_from_odometry_topic" default="$(arg dynamic_update_of_assembly_configuration_from_odometry_topic)" />
<arg name="dynamic_update_of_assembly_configuration_from_imu_topic" default="$(arg dynamic_update_of_assembly_configuration_from_imu_topic)" />
<arg name="min_range_cutoff_percentage_offset" default="$(arg min_range_cutoff_percentage_offset)" />
<arg name="max_range_cutoff_percentage_offset" default="$(arg max_range_cutoff_percentage_offset)" />
<arg name="min_number_of_scans_to_assemble_per_cloud" default="$(arg min_number_of_scans_to_assemble_per_cloud)" />
<arg name="max_number_of_scans_to_assemble_per_cloud" default="$(arg max_number_of_scans_to_assemble_per_cloud)" />
<arg name="min_timeout_seconds_for_cloud_assembly" default="$(arg min_timeout_seconds_for_cloud_assembly)" />
<arg name="max_timeout_seconds_for_cloud_assembly" default="$(arg max_timeout_seconds_for_cloud_assembly)" />
<arg name="max_linear_velocity" default="$(arg max_linear_velocity)" />
<arg name="max_angular_velocity" default="$(arg max_angular_velocity)" />
<arg name="target_frame" default="$(arg laser_assembly_frame)" />
<arg name="recovery_frame" default="$(arg odom_frame_id)" if="$(arg assemble_lasers_on_map_frame)" />
<arg name="recovery_frame" default="" unless="$(arg assemble_lasers_on_map_frame)" />
<arg name="initial_recovery_transform_in_base_link_to_target" default="$(arg robot_initial_pose_in_base_to_map)" />
<arg name="base_link_frame_id" default="$(arg base_link_frame_id)" />
<arg name="motion_estimation_source_frame_id" default="$(arg laser_assembly_motion_estimation_source_frame_id)" />
<arg name="motion_estimation_target_frame_id" default="$(arg laser_assembly_motion_estimation_target_frame_id)" />
<arg name="recovery_to_target_frame_transform_initial_x" default="$(arg robot_initial_x)" />
<arg name="recovery_to_target_frame_transform_initial_y" default="$(arg robot_initial_y)" />
<arg name="recovery_to_target_frame_transform_initial_z" default="$(arg robot_initial_z)" />
<arg name="recovery_to_target_frame_transform_initial_roll" default="$(arg robot_initial_roll)" />
<arg name="recovery_to_target_frame_transform_initial_pitch" default="$(arg robot_initial_pitch)" />
<arg name="recovery_to_target_frame_transform_initial_yaw" default="$(arg robot_initial_yaw)" />
<arg name="nodes_respawn" default="$(arg nodes_respawn)" />
</include>
<!-- OctoMap for dynamic map update -->
<group if="$(arg use_octomap_for_dynamic_map_update)" ns="$(arg nodes_namespace)" >
<include file="$(find dynamic_robot_localization)/launch/octo_map.launch" >
<arg name="octomap_file" default="$(arg octomap_file)" />
<arg name="cloud_in" default="$(arg octomap_pointcloud_topic)" />
<arg name="map_frame_id" default="$(arg map_frame_id)" />
<arg name="base_frame_id" default="$(arg base_link_frame_id)" />
<arg name="sensor_frame_id" default="$(arg octomap_sensor_frame_id)" />
<arg name="override_sensor_z" default="$(arg octomap_override_sensor_z)" />
<arg name="override_sensor_z_value" default="$(arg octomap_override_sensor_z_value)" />
<arg name="resolution" default="$(arg octomap_resolution)" />
<arg name="minimum_amount_of_time_between_ros_msg_publishing" default="$(arg octomap_minimum_amount_of_time_between_ros_msg_publishing)" />
<arg name="minimum_number_of_integrations_before_ros_msg_publishing" default="$(arg octomap_minimum_number_of_integrations_before_ros_msg_publishing)" />
<arg name="cloud_out_topic" default="$(arg octomap_cloud_out_topic)" />
<arg name="map_out_topic" default="$(arg reference_costmap_topic_updated)" if="$(arg use_octomap_only_to_build_occupancy_grid)" />
<arg name="map_out_topic" default="$(arg reference_costmap_topic)" unless="$(arg use_octomap_only_to_build_occupancy_grid)" />
<arg name="nodes_respawn" default="$(arg nodes_respawn)" />
</include>
<group if="$(arg reference_pointcloud_available)" >
<node name="map_server" pkg="map_server" type="map_server" args="$(arg initial_2d_map_file)" respawn="$(arg nodes_respawn)" clear_params="true" output="screen" unless="$(arg reference_pointcloud_type_3d)" >
<param name="frame_id" type="str" value="$(arg map_frame_id)" />
<remap from="map" to="initial_2d_map" />
</node>
</group>
</group>
</launch>