hector_mapping.launch 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. <!--
  2. Author: corvin
  3. Description: hector mapping.
  4. History:
  5. 20180601: initial this file.
  6. -->
  7. <launch>
  8. <arg name="map_scanmatch_frame_name" default="scanmatcher_frame"/>
  9. <arg name="pub_map_odom_transform" default="true"/>
  10. <arg name="scan_queue_size" default="10"/>
  11. <arg name="base_frame" default="/base_link" />
  12. <arg name="odom_frame" default="/odom" />
  13. <arg name="map_frame" default="/map" />
  14. <arg name="scan_topic" default="/scan" />
  15. <arg name="map_size" default="512" />
  16. <!-- startup ydlidar -->
  17. <include file="$(find ydlidar)/launch/lidar.launch" />
  18. <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
  19. <!-- Frame names -->
  20. <param name="map_frame" value="$(arg map_frame)" />
  21. <param name="base_frame" value="$(arg base_frame)" />
  22. <param name="odom_frame" value="$(arg odom_frame)" />
  23. <!-- Map resolution/size/start point -->
  24. <param name="map_resolution" value="0.04"/>
  25. <param name="map_size" value="$(arg map_size)"/>
  26. <param name="map_start_x" value="0.2" />
  27. <param name="map_start_y" value="0.2" />
  28. <!-- Map update parameters -->
  29. <param name="map_update_distance_thresh" value="0.45" />
  30. <param name="map_update_angle_thresh" value="0.30" />
  31. <param name="map_pub_period" value="2.2" />
  32. <param name="map_multi_res_levels" value="2" />
  33. <param name="update_factor_free" value="0.4" />
  34. <param name="update_factor_occupied" value="0.9" />
  35. <!-- lidar laser parameters -->
  36. <param name="scan_topic" value="$(arg scan_topic)" />
  37. <param name="laser_min_dist" value="0.06" />
  38. <param name="laser_max_dist" value="4.09" />
  39. <param name="laser_z_min_value" value="-1.0" />
  40. <param name="laser_z_max_value" value="1.0" />
  41. <param name="output_timing" value="false"/>
  42. <param name="scan_subscriber_queue_size" value="$(arg scan_queue_size)"/>
  43. <param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
  44. <param name="advertise_map_service" value="true" />
  45. <param name="use_tf_scan_transformation" value="true" />
  46. <param name="use_tf_pose_start_estimate" value="true" />
  47. <param name="tf_map_scanmatch_transform_frame_name" value="$(arg map_scanmatch_frame_name)" />
  48. </node>
  49. <node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0.0 0.0 0.0 0 0 0.0 /map /odom 100"/>
  50. </launch>