amcl_sick.launch 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. <launch>
  2. <!-->
  3. <node pkg="beginner_tutorials" type="talker" name="talker"/>
  4. <-->
  5. <param name="use_sim_time" value="true" />
  6. <node pkg="map_server" type="map_server" name="map_server" args="/home/youchen/Documents/git_ws/map1.yaml"/>
  7. <node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 1 /base_link /laser 30" />
  8. <!--><node pkg="tf" type="static_transform_publisher" name="odom_base_link_broadcaster"
  9. args="0.1 0 0 0 0 0 1 odom base_link 30" /><-->
  10. <!--><node pkg="tf" type="static_transform_publisher" name="odom_raw_to_map_broadcaster"
  11. args="0.1 0 0 0 0 0 1 map odom_raw 30" /><-->
  12. <node pkg="laser_scan_matcher" type="laser_scan_matcher_node"
  13. name="laser_scan_matcher_node" output="screen">
  14. <param name="max_iterations" value="40"/>
  15. <param name="fixed_frame" value="/odom"/>
  16. <param name="base_frame" value="/base_link"/>
  17. </node>
  18. <!-- amcl node -->
  19. <node pkg="amcl" type="amcl" name="amcl" output="screen">
  20. <param name="odom_frame_id" value="odom"/>
  21. <param name="base_frame_id" value="base_link"/>
  22. <param name="global_frame_id" value="map"/>
  23. <!-- Publish scans from best pose at a max of 10 Hz -->
  24. <param name="use_map_topic" value="false"/>
  25. <param name="odom_model_type" value="omni"/>
  26. <param name="odom_alpha5" value="0.1"/>
  27. <param name="transform_tolerance" value="0.05" />
  28. <param name="gui_publish_rate" value="5.0"/>
  29. <param name="laser_max_beams" value="100"/>
  30. <param name="min_particles" value="100"/>
  31. <param name="max_particles" value="1000"/>
  32. <param name="kld_err" value="0.05"/>
  33. <param name="kld_z" value="0.99"/>
  34. <param name="odom_alpha1" value="0.1"/>
  35. <param name="odom_alpha2" value="0.1"/>
  36. <!-- translation std dev, m -->
  37. <param name="odom_alpha3" value="0.1"/>
  38. <param name="odom_alpha4" value="0.1"/>
  39. <param name="laser_z_hit" value="0.9"/>
  40. <param name="laser_z_short" value="0.05"/>
  41. <param name="laser_z_max" value="0.05"/>
  42. <param name="laser_z_rand" value="0.5"/>
  43. <param name="laser_sigma_hit" value="0.2"/>
  44. <param name="laser_lambda_short" value="0.1"/>
  45. <param name="laser_lambda_short" value="0.1"/>
  46. <param name="laser_model_type" value="likelihood_field"/>
  47. <!-- <param name="laser_model_type" value="beam"/> -->
  48. <param name="laser_min_range" value="-1.0"/>
  49. <param name="laser_max_range" value="-1.0"/>
  50. <param name="laser_likelihood_max_dist" value="2.0"/>
  51. <param name="update_min_d" value="0.1"/>
  52. <param name="update_min_a" value="0.5"/>
  53. <param name="resample_interval" value="1"/>
  54. <param name="transform_tolerance" value="0.1"/>
  55. <param name="recovery_alpha_slow" value="0.0"/>
  56. <param name="recovery_alpha_fast" value="0.0"/>
  57. <param name="initial_cov_xx" value="16"/>
  58. <param name="initial_cov_yy" value="16"/>
  59. <param name="initial_cov_aa" value="0.00685"/>
  60. </node>
  61. </launch>