amcl_rplidar_a1.launch 2.1 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253
  1. <launch>
  2. <!-- Run the map server with a map -->
  3. <node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/my_room.yaml" />
  4. <!-- startup rplidar node -->
  5. <include file="$(find robot_navigation)/launch/rplidar.launch" />
  6. <!-- startup move_base node -->
  7. <include file="$(find robot_navigation)/launch/move_base.launch" />
  8. <!-- Run amcl -->
  9. <node pkg="amcl" type="amcl" name="robot_amcl">
  10. <param name="odom_model_type" value="omni"/>
  11. <param name="base_frame_id" value="base_footprint"/>
  12. <param name="global_frame_id" value="map"/>
  13. <param name="odom_frame_id" value="odom_combined"/>
  14. <param name="use_map_topic" value="true"/>
  15. <param name="odom_alpha5" value="0.1"/>
  16. <param name="transform_tolerance" value="0.5" />
  17. <param name="gui_publish_rate" value="1.0"/>
  18. <param name="laser_max_beams" value="300"/>
  19. <param name="min_particles" value="500"/>
  20. <param name="max_particles" value="5000"/>
  21. <param name="kld_err" value="0.1"/>
  22. <param name="kld_z" value="0.99"/>
  23. <param name="odom_alpha1" value="0.2"/>
  24. <param name="odom_alpha2" value="0.2"/>
  25. <param name="odom_alpha3" value="0.2"/>
  26. <param name="odom_alpha4" value="0.2"/>
  27. <param name="odom_alpha5" value="0.2"/>
  28. <param name="laser_z_hit" value="0.9"/>
  29. <param name="laser_z_short" value="0.05"/>
  30. <param name="laser_z_max" value="0.05"/>
  31. <param name="laser_z_rand" value="0.05"/>
  32. <param name="laser_sigma_hit" value="0.2"/>
  33. <param name="laser_lambda_short" value="0.1"/>
  34. <param name="laser_model_type" value="likelihood_field"/>
  35. <param name="laser_model_type" value="beam"/>
  36. <param name="laser_min_range" value="0.14"/>
  37. <param name="laser_max_range" value="7.0"/>
  38. <param name="laser_likelihood_max_dist" value="2.0"/>
  39. <param name="update_min_d" value="0.2"/>
  40. <param name="update_min_a" value="0.5"/>
  41. <param name="resample_interval" value="2"/>
  42. <param name="transform_tolerance" value="3.0"/>
  43. <param name="recovery_alpha_slow" value="0.0"/>
  44. <param name="recovery_alpha_fast" value="0.0"/>
  45. </node>
  46. </launch>