hdl_graph_slam_400.launch 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215
  1. <?xml version="1.0"?>
  2. <launch>
  3. <!--
  4. 前面4个节点的代码文件在hdl_graph_slam/apps/... 是在ROS中注册的插件
  5. prefiltering_nodelet: !!!! 点云滤波 !!!!
  6. 包(pkg): nodelet
  7. 类型(type): nodelet
  8. 名称(name): prefiltering_nodelet
  9. 作用:加载并执行hdl_graph_slam包中的PrefilteringNodelet,用于对激光雷达点云数据进行预处理,包括距离滤波、下采样和离群点移除。
  10. scan_matching_odometry_nodelet: !!!!帧间匹配,也就是激光里程计(前端里程计) !!!!
  11. 包(pkg): nodelet
  12. 类型(type): nodelet
  13. 名称(name): scan_matching_odometry_nodelet
  14. 作用:加载并执行hdl_graph_slam包中的ScanMatchingOdometryNodelet,用于通过扫描匹配进行里程计估计。
  15. floor_detection_nodelet (条件启动,取决于 enable_floor_detection 参数): !!!!地平面检测 !!!!
  16. 包(pkg): nodelet
  17. 类型(type): nodelet
  18. 名称(name): floor_detection_nodelet
  19. 作用:加载并执行hdl_graph_slam包中的FloorDetectionNodelet,用于检测地面平面。
  20. hdl_graph_slam_nodelet: !!!!后端概率图构建 !!!!
  21. 包(pkg): nodelet
  22. 类型(type): nodelet
  23. 名称(name): hdl_graph_slam_nodelet
  24. 作用:加载并执行hdl_graph_slam包中的HdlGraphSlamNodelet,用于执行基于图的SLAM(Simultaneous Localization and Mapping)。
  25. lidar2base_publisher:
  26. 包(pkg): tf
  27. 类型(type): static_transform_publisher
  28. 作用:发布从base_link到velodyne(激光雷达)的静态坐标变换。这里的参数0 0 0 0 0 0表示没有平移和旋转,即激光雷达与base_link坐标系重合。
  29. velodyne_nodelet_manager:
  30. 包(pkg): nodelet
  31. 类型(type): nodelet
  32. 名称(name): velodyne_nodelet_manager
  33. 作用:作为一个节点管理器,用于管理其他节点(nodelet)。
  34. map2odom_publisher:
  35. 包(pkg): hdl_graph_slam
  36. 类型(type): map2odom_publisher.py
  37. 名称(name): map2odom_publisher
  38. 作用:这是一个Python脚本,用于发布从地图到里程计的变换。
  39. -->
  40. <!-- 使用仿真时间 -->
  41. <param name="use_sim_time" value="true" />
  42. <!-- 回放rosbag文件 -->
  43. <!-- /home/mj/hdl_slam/hdl_400.bag -->
  44. <node pkg="rosbag" type="play" name="player" output="screen" args="--clock --start 20 /home/mj/hdl_slam/hdl_400.bag"/>
  45. <node pkg="hdl_graph_slam" type="laser2cloud" name="laser2cloud" output="log" />
  46. <node name="rviz" pkg="rviz" type="rviz" args="-d $(find hdl_graph_slam)/rviz/hdl_graph_slam.rviz"/>
  47. <!-- 线程池 用另外一个线程实现后端 -->
  48. <!-- arguments -->
  49. <arg name="nodelet_manager" default="velodyne_nodelet_manager" />
  50. <arg name="enable_floor_detection" default="true" />
  51. <arg name="enable_gps" default="false" />
  52. <arg name="enable_imu_acc" default="false" />
  53. <arg name="enable_imu_ori" default="false" />
  54. <arg name="points_topic" default="/velodyne_points" />
  55. <arg name="map_frame_id" default="map" />
  56. <arg name="lidar_odom_frame_id" default="odom" />
  57. <!-- optional arguments -->
  58. <arg name="enable_robot_odometry_init_guess" default="false" />
  59. <arg name="robot_odom_frame_id" default="robot_odom" />
  60. <!-- transformation between lidar and base_link -->
  61. <node pkg="tf" type="static_transform_publisher" name="lidar2base_publisher" args="0 0 0 0 0 0 base_link velodyne 10" />
  62. <!-- in case you use velodyne_driver, comment out the following line -->
  63. <node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" output="screen"/>
  64. <!-- prefiltering_nodelet -->
  65. <node pkg="nodelet" type="nodelet" name="prefiltering_nodelet" args="load hdl_graph_slam/PrefilteringNodelet $(arg nodelet_manager)">
  66. <remap from="/velodyne_points" to="$(arg points_topic)" />
  67. <!-- in case base_link_frame is blank, mapping will be performed in the lidar frame -->
  68. <param name="base_link_frame" value="base_link" />
  69. <!-- distance filter -->
  70. <param name="use_distance_filter" value="true" />
  71. <param name="distance_near_thresh" value="0.1" />
  72. <param name="distance_far_thresh" value="100.0" />
  73. <!-- NONE, VOXELGRID, or APPROX_VOXELGRID -->
  74. <param name="downsample_method" value="VOXELGRID" />
  75. <param name="downsample_resolution" value="0.1" />
  76. <!-- NONE, RADIUS, or STATISTICAL -->
  77. <param name="outlier_removal_method" value="RADIUS" />
  78. <param name="statistical_mean_k" value="30" />
  79. <param name="statistical_stddev" value="1.2" />
  80. <param name="radius_radius" value="0.5" />
  81. <param name="radius_min_neighbors" value="2" />
  82. </node>
  83. <!-- scan_matching_odometry_nodelet -->
  84. <node pkg="nodelet" type="nodelet" name="scan_matching_odometry_nodelet" args="load hdl_graph_slam/ScanMatchingOdometryNodelet $(arg nodelet_manager)" output="screen">
  85. <param name="points_topic" value="$(arg points_topic)" />
  86. <param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
  87. <param name="robot_odom_frame_id" value="$(arg robot_odom_frame_id)" />
  88. <param name="keyframe_delta_trans" value="1.0" />
  89. <param name="keyframe_delta_angle" value="1.0" />
  90. <param name="keyframe_delta_time" value="10000.0" />
  91. <param name="transform_thresholding" value="false" />
  92. <param name="enable_robot_odometry_init_guess" value="$(arg enable_robot_odometry_init_guess)" />
  93. <param name="max_acceptable_trans" value="1.0" />
  94. <param name="max_acceptable_angle" value="1.0" />
  95. <param name="downsample_method" value="NONE" />
  96. <param name="downsample_resolution" value="0.1" />
  97. <!-- ICP, GICP, NDT, GICP_OMP, NDT_OMP, FAST_GICP(recommended), or FAST_VGICP -->
  98. <param name="registration_method" value="FAST_GICP" />
  99. <param name="reg_num_threads" value="0" />
  100. <param name="reg_transformation_epsilon" value="0.1"/>
  101. <param name="reg_maximum_iterations" value="64"/>
  102. <param name="reg_max_correspondence_distance" value="2.0"/>
  103. <param name="reg_max_optimizer_iterations" value="20"/>
  104. <param name="reg_use_reciprocal_correspondences" value="false"/>
  105. <param name="reg_correspondence_randomness" value="20"/>
  106. <param name="reg_resolution" value="1.0" />
  107. <param name="reg_nn_search_method" value="DIRECT7" />
  108. </node>
  109. <!-- floor_detection_nodelet -->
  110. <node pkg="nodelet" type="nodelet" name="floor_detection_nodelet" args="load hdl_graph_slam/FloorDetectionNodelet $(arg nodelet_manager)" if="$(arg enable_floor_detection)">
  111. <param name="points_topic" value="$(arg points_topic)" />
  112. <param name="tilt_deg" value="0.0" />
  113. <param name="sensor_height" value="2.0" />
  114. <param name="height_clip_range" value="1.0" />
  115. <param name="floor_pts_thresh" value="512" />
  116. <param name="use_normal_filtering" value="true" />
  117. <param name="normal_filter_thresh" value="20.0" />
  118. </node>
  119. <!-- hdl_graph_slam_nodelet -->
  120. <node pkg="nodelet" type="nodelet" name="hdl_graph_slam_nodelet" args="load hdl_graph_slam/HdlGraphSlamNodelet $(arg nodelet_manager)" output="screen">
  121. <param name="points_topic" value="$(arg points_topic)" />
  122. <!-- frame settings -->
  123. <param name="map_frame_id" value="$(arg map_frame_id)" />
  124. <param name="odom_frame_id" value="$(arg lidar_odom_frame_id)" />
  125. <!-- optimization params -->
  126. <!-- typical solvers: gn_var, gn_fix6_3, gn_var_cholmod, lm_var, lm_fix6_3, lm_var_cholmod, ... -->
  127. <param name="g2o_solver_type" value="lm_var_cholmod" />
  128. <param name="g2o_solver_num_iterations" value="512" />
  129. <!-- constraint switches -->
  130. <param name="enable_gps" value="$(arg enable_gps)" />
  131. <param name="enable_imu_acceleration" value="$(arg enable_imu_acc)" />
  132. <param name="enable_imu_orientation" value="$(arg enable_imu_ori)" />
  133. <!-- keyframe registration params -->
  134. <param name="max_keyframes_per_update" value="10" />
  135. <param name="keyframe_delta_trans" value="2.0" />
  136. <param name="keyframe_delta_angle" value="2.0" />
  137. <!-- fix first node for optimization stability -->
  138. <param name="fix_first_node" value="true"/>
  139. <param name="fix_first_node_stddev" value="10 10 10 1 1 1"/>
  140. <param name="fix_first_node_adaptive" value="true"/>
  141. <!-- loop closure params -->
  142. <param name="distance_thresh" value="15.0" />
  143. <param name="accum_distance_thresh" value="25.0" />
  144. <param name="min_edge_interval" value="15.0" />
  145. <param name="fitness_score_thresh" value="2.5" />
  146. <!-- scan matching params -->
  147. <param name="registration_method" value="FAST_GICP" />
  148. <param name="reg_num_threads" value="0" />
  149. <param name="reg_transformation_epsilon" value="0.1"/>
  150. <param name="reg_maximum_iterations" value="64"/>
  151. <param name="reg_max_correspondence_distance" value="2.0"/>
  152. <param name="reg_max_optimizer_iterations" value="20"/>
  153. <param name="reg_use_reciprocal_correspondences" value="false"/>
  154. <param name="reg_correspondence_randomness" value="20"/>
  155. <param name="reg_resolution" value="1.0" />
  156. <param name="reg_nn_search_method" value="DIRECT7" />
  157. <!-- edge params -->
  158. <!-- GPS -->
  159. <param name="gps_edge_robust_kernel" value="NONE" />
  160. <param name="gps_edge_robust_kernel_size" value="1.0" />
  161. <param name="gps_edge_stddev_xy" value="20.0" />
  162. <param name="gps_edge_stddev_z" value="5.0" />
  163. <!-- IMU orientation -->
  164. <param name="imu_orientation_edge_robust_kernel" value="NONE" />
  165. <param name="imu_orientation_edge_stddev" value="1.0" />
  166. <!-- IMU acceleration (gravity vector) -->
  167. <param name="imu_acceleration_edge_robust_kernel" value="NONE" />
  168. <param name="imu_acceleration_edge_stddev" value="1.0" />
  169. <!-- ground plane -->
  170. <param name="floor_edge_robust_kernel" value="NONE" />
  171. <param name="floor_edge_stddev" value="10.0" />
  172. <!-- scan matching -->
  173. <!-- robust kernels: NONE, Cauchy, DCS, Fair, GemanMcClure, Huber, PseudoHuber, Saturated, Tukey, Welsch -->
  174. <param name="odometry_edge_robust_kernel" value="NONE" />
  175. <param name="odometry_edge_robust_kernel_size" value="1.0" />
  176. <param name="loop_closure_edge_robust_kernel" value="Huber" />
  177. <param name="loop_closure_edge_robust_kernel_size" value="1.0" />
  178. <param name="use_const_inf_matrix" value="false" />
  179. <param name="const_stddev_x" value="0.5" />
  180. <param name="const_stddev_q" value="0.1" />
  181. <param name="var_gain_a" value="20.0" />
  182. <param name="min_stddev_x" value="0.1" />
  183. <param name="max_stddev_x" value="5.0" />
  184. <param name="min_stddev_q" value="0.05" />
  185. <param name="max_stddev_q" value="0.2" />
  186. <!-- update params -->
  187. <param name="graph_update_interval" value="3.0" />
  188. <param name="map_cloud_update_interval" value="10.0" />
  189. <param name="map_cloud_resolution" value="0.05" />
  190. </node>
  191. <node pkg="hdl_graph_slam" type="map2odom_publisher.py" name="map2odom_publisher" output="screen"/>
  192. </launch>