hdl_graph_slam.launch 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. <?xml version="1.0"?>
  2. <launch>
  3. <!-- arguments -->
  4. <arg name="nodelet_manager" default="velodyne_nodelet_manager" />
  5. <arg name="enable_floor_detection" default="false" />
  6. <arg name="enable_gps" default="false" />
  7. <arg name="enable_imu_acc" default="false" />
  8. <arg name="enable_imu_ori" default="false" />
  9. <!-- hdl_graph_slam will publish its estimated pose from odom to base_link within the following structure -->
  10. <!-- ***** map -> odom -> base_link -> velodyne ***** -->
  11. <!-- these can be named in the following -->
  12. <!-- topic for hdl to find velodyne points -->
  13. <arg name="points_topic" default="/velodyne_points" />
  14. <!-- what should the map frame be called -->
  15. <arg name="map_frame_id" default="map" />
  16. <!-- what should the base link frame be called -->
  17. <arg name="base_link_frame_id" default="base_link" />
  18. <!-- what should the odom frame be called -->
  19. <arg name="lidar_odom_frame_id" default="odom" />
  20. <!-- hdl_graph_slam will also publish an odom message -->
  21. <!-- what should the topic be for odom messages published by hdl-graph-slam -->
  22. <arg name="published_odom_topic" default="/odom" />
  23. <!-- optional arguments -->
  24. <arg name="enable_robot_odometry_init_guess" default="false" />
  25. <arg name="robot_odom_frame_id" default="robot_odom" />
  26. <!-- transformation between lidar and base_link -->
  27. <node pkg="tf" type="static_transform_publisher" name="lidar2base_publisher" args="0 0 0 0 0 0 $(arg base_link_frame_id) velodyne 10" />
  28. <!-- in case you use velodyne_driver, comment out the following line -->
  29. <node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" output="screen"/>
  30. <!-- prefiltering_nodelet -->
  31. <node pkg="nodelet" type="nodelet" name="prefiltering_nodelet" args="load hdl_graph_slam/PrefilteringNodelet $(arg nodelet_manager)">
  32. <remap from="/velodyne_points" to="$(arg points_topic)" />
  33. <!-- in case base_link_frame is blank, mapping will be performed in the lidar frame -->
  34. <param name="base_link_frame" value="$(arg base_link_frame_id)" />
  35. <!-- distance filter -->
  36. <param name="use_distance_filter" value="false" />
  37. <param name="distance_near_thresh" value="0.1" />
  38. <param name="distance_far_thresh" value="1000.0" />
  39. <!-- NONE, VOXELGRID, or APPROX_VOXELGRID -->
  40. <param name="downsample_method" value="VOXELGRID" />
  41. <param name="downsample_resolution" value="0.1" />
  42. <!-- NONE, RADIUS, or STATISTICAL -->
  43. <param name="outlier_removal_method" value="NONE" />
  44. <param name="statistical_mean_k" value="30" />
  45. <param name="statistical_stddev" value="1.2" />
  46. <param name="radius_radius" value="0.5" />
  47. <param name="radius_min_neighbors" value="2" />
  48. </node>
  49. <!-- scan_matching_odometry_nodelet -->
  50. <node pkg="nodelet" type="nodelet" name="scan_matching_odometry_nodelet" args="load hdl_graph_slam/ScanMatchingOdometryNodelet $(arg nodelet_manager)">
  51. <param name="points_topic" value="$(arg points_topic)" />
  52. <!-- published_odom_topic -->
  53. <param name="published_odom_topic" value="$(arg published_odom_topic)" />
  54. <param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
  55. <param name="robot_odom_frame_id" value="$(arg robot_odom_frame_id)" />
  56. <param name="keyframe_delta_trans" value="1.0" />
  57. <param name="keyframe_delta_angle" value="1.0" />
  58. <param name="keyframe_delta_time" value="10000.0" />
  59. <param name="transform_thresholding" value="false" />
  60. <param name="enable_robot_odometry_init_guess" value="$(arg enable_robot_odometry_init_guess)" />
  61. <param name="max_acceptable_trans" value="1.0" />
  62. <param name="max_acceptable_angle" value="1.0" />
  63. <param name="downsample_method" value="NONE" />
  64. <param name="downsample_resolution" value="0.1" />
  65. <!-- ICP, GICP, NDT, GICP_OMP, NDT_OMP, FAST_GICP(recommended), or FAST_VGICP -->
  66. <param name="registration_method" value="FAST_GICP" />
  67. <param name="reg_num_threads" value="0" />
  68. <param name="reg_transformation_epsilon" value="0.01"/>
  69. <param name="reg_maximum_iterations" value="64"/>
  70. <param name="reg_max_correspondence_distance" value="2.5"/>
  71. <param name="reg_max_optimizer_iterations" value="20"/>
  72. <param name="reg_use_reciprocal_correspondences" value="false"/>
  73. <param name="reg_correspondence_randomness" value="20"/>
  74. <param name="reg_resolution" value="1.0" />
  75. <param name="reg_nn_search_method" value="DIRECT7" />
  76. </node>
  77. <!-- floor_detection_nodelet -->
  78. <node pkg="nodelet" type="nodelet" name="floor_detection_nodelet" args="load hdl_graph_slam/FloorDetectionNodelet $(arg nodelet_manager)" if="$(arg enable_floor_detection)">
  79. <param name="points_topic" value="$(arg points_topic)" />
  80. <param name="tilt_deg" value="0.0" />
  81. <param name="sensor_height" value="2.0" />
  82. <param name="height_clip_range" value="1.0" />
  83. <param name="floor_pts_thresh" value="512" />
  84. <param name="use_normal_filtering" value="true" />
  85. <param name="normal_filter_thresh" value="20.0" />
  86. </node>
  87. <!-- hdl_graph_slam_nodelet -->
  88. <node pkg="nodelet" type="nodelet" name="hdl_graph_slam_nodelet" args="load hdl_graph_slam/HdlGraphSlamNodelet $(arg nodelet_manager)">
  89. <param name="points_topic" value="$(arg points_topic)" />
  90. <!-- published_odom_topic -->
  91. <param name="published_odom_topic" value="$(arg published_odom_topic)" />
  92. <!-- frame settings -->
  93. <param name="map_frame_id" value="$(arg map_frame_id)" />
  94. <param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
  95. <!-- optimization params -->
  96. <!-- typical solvers: gn_var, gn_fix6_3, gn_var_cholmod, lm_var, lm_fix6_3, lm_var_cholmod, ... -->
  97. <param name="g2o_solver_type" value="lm_var_cholmod" />
  98. <param name="g2o_solver_num_iterations" value="512" />
  99. <!-- constraint switches -->
  100. <param name="enable_gps" value="$(arg enable_gps)" />
  101. <param name="enable_imu_acceleration" value="$(arg enable_imu_acc)" />
  102. <param name="enable_imu_orientation" value="$(arg enable_imu_ori)" />
  103. <!-- keyframe registration params -->
  104. <param name="max_keyframes_per_update" value="10" />
  105. <param name="keyframe_delta_trans" value="2.0" />
  106. <param name="keyframe_delta_angle" value="2.0" />
  107. <!-- fix first node for optimization stability -->
  108. <param name="fix_first_node" value="true"/>
  109. <param name="fix_first_node_stddev" value="10 10 10 1 1 1"/>
  110. <param name="fix_first_node_adaptive" value="true"/>
  111. <!-- loop closure params -->
  112. <param name="distance_thresh" value="20.0" />
  113. <param name="accum_distance_thresh" value="35.0" />
  114. <param name="min_edge_interval" value="5.0" />
  115. <param name="fitness_score_thresh" value="0.5" />
  116. <!-- scan matching params -->
  117. <param name="registration_method" value="FAST_GICP" />
  118. <param name="reg_num_threads" value="4" />
  119. <param name="reg_transformation_epsilon" value="0.01"/>
  120. <param name="reg_maximum_iterations" value="64"/>
  121. <param name="reg_max_correspondence_distance" value="2.5"/>
  122. <param name="reg_max_optimizer_iterations" value="20"/>
  123. <param name="reg_use_reciprocal_correspondences" value="false"/>
  124. <param name="reg_correspondence_randomness" value="20"/>
  125. <param name="reg_resolution" value="1.0" />
  126. <param name="reg_nn_search_method" value="DIRECT7" />
  127. <!-- edge params -->
  128. <!-- GPS -->
  129. <param name="gps_edge_robust_kernel" value="NONE" />
  130. <param name="gps_edge_robust_kernel_size" value="1.0" />
  131. <param name="gps_edge_stddev_xy" value="20.0" />
  132. <param name="gps_edge_stddev_z" value="5.0" />
  133. <!-- IMU orientation -->
  134. <param name="imu_orientation_edge_robust_kernel" value="NONE" />
  135. <param name="imu_orientation_edge_stddev" value="1.0" />
  136. <!-- IMU acceleration (gravity vector) -->
  137. <param name="imu_acceleration_edge_robust_kernel" value="NONE" />
  138. <param name="imu_acceleration_edge_stddev" value="1.0" />
  139. <!-- ground plane -->
  140. <param name="floor_edge_robust_kernel" value="NONE" />
  141. <param name="floor_edge_stddev" value="10.0" />
  142. <!-- scan matching -->
  143. <!-- robust kernels: NONE, Cauchy, DCS, Fair, GemanMcClure, Huber, PseudoHuber, Saturated, Tukey, Welsch -->
  144. <param name="odometry_edge_robust_kernel" value="NONE" />
  145. <param name="odometry_edge_robust_kernel_size" value="1.0" />
  146. <param name="loop_closure_edge_robust_kernel" value="Huber" />
  147. <param name="loop_closure_edge_robust_kernel_size" value="1.0" />
  148. <param name="use_const_inf_matrix" value="false" />
  149. <param name="const_stddev_x" value="0.5" />
  150. <param name="const_stddev_q" value="0.1" />
  151. <param name="var_gain_a" value="20.0" />
  152. <param name="min_stddev_x" value="0.1" />
  153. <param name="max_stddev_x" value="5.0" />
  154. <param name="min_stddev_q" value="0.05" />
  155. <param name="max_stddev_q" value="0.2" />
  156. <!-- update params -->
  157. <param name="graph_update_interval" value="3.0" />
  158. <param name="map_cloud_update_interval" value="10.0" />
  159. <param name="map_cloud_resolution" value="0.05" />
  160. </node>
  161. <node pkg="hdl_graph_slam" type="map2odom_publisher.py" name="map2odom_publisher" >
  162. <param name="map_frame_id" value="$(arg map_frame_id)" />
  163. <param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
  164. </node>
  165. </launch>