|
@@ -1,5 +1,10 @@
|
|
|
<!--
|
|
|
Description:使用EAI的X2L雷达进行amcl定位,加载地图进行自动导航,这里加载的局部路径规划算法是dwa.
|
|
|
+ odom_alpha1:从旋转角度估计机器人里程计的旋转噪声
|
|
|
+ odom_alpha2:机器人平移分量中的里程计旋转噪音,噪声在机器人左右两边分布
|
|
|
+ odom_alpha3:机器人平移过程中的里程计平移噪音,沿着机器人前进方向分布
|
|
|
+ odom_alpha4:机器人旋转过程中的里程计平移噪音,斜角方向上的运动噪声
|
|
|
+ odom_alpha5:从旋转角度考虑机器人里程计的旋转噪声
|
|
|
Author: corvin
|
|
|
History:
|
|
|
20200326:init this file.
|
|
@@ -7,20 +12,20 @@
|
|
|
20220810:在启动amcl算法进行自动导航时,先将robot_bringup.launch启动.
|
|
|
-->
|
|
|
<launch>
|
|
|
- <!-- startup robot bringup -->
|
|
|
+ <!--(1) startup robot bringup -->
|
|
|
<include file="$(find robot_bringup)/launch/robot_bringup.launch" />
|
|
|
|
|
|
- <!-- Run the map server with a map -->
|
|
|
+ <!--(2) Run the map server with loading a map -->
|
|
|
<node name="map_server" pkg="map_server" type="map_server" args="$(find robot_navigation)/maps/test_map.yaml" />
|
|
|
|
|
|
- <!-- startup ydlidar X2L node -->
|
|
|
+ <!--(3) startup ydlidar X2L node -->
|
|
|
<include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
|
|
|
|
|
|
- <!-- startup move_base node -->
|
|
|
+ <!--(4) startup move_base node -->
|
|
|
<include file="$(find robot_navigation)/launch/move_base.launch" />
|
|
|
|
|
|
- <!-- Run amcl node -->
|
|
|
- <node pkg="amcl" type="amcl" name="robot_amcl">
|
|
|
+ <!--(5) Run amcl node -->
|
|
|
+ <node pkg="amcl" type="amcl" name="robot_amcl" output="screen">
|
|
|
<param name="odom_model_type" value="diff-corrected"/>
|
|
|
|
|
|
<param name="base_frame_id" value="base_footprint"/>
|
|
@@ -34,14 +39,15 @@
|
|
|
<param name="transform_tolerance" value="3"/>
|
|
|
<param name="gui_publish_rate" value="10.0"/>
|
|
|
<param name="laser_max_beams" value="300"/>
|
|
|
- <param name="min_particles" value="500"/>
|
|
|
- <param name="max_particles" value="2500"/>
|
|
|
+ <param name="min_particles" value="100"/>
|
|
|
+ <param name="max_particles" value="2000"/>
|
|
|
<param name="kld_err" value="0.1"/>
|
|
|
<param name="kld_z" value="0.99"/>
|
|
|
- <param name="odom_alpha1" value="0.2"/>
|
|
|
+
|
|
|
+ <param name="odom_alpha1" value="0.1"/>
|
|
|
<param name="odom_alpha2" value="0.1"/>
|
|
|
<param name="odom_alpha3" value="0.1"/>
|
|
|
- <param name="odom_alpha4" value="0.2"/>
|
|
|
+ <param name="odom_alpha4" value="0.1"/>
|
|
|
<param name="odom_alpha5" value="0.0"/>
|
|
|
|
|
|
<param name="save_pose_rate" value="0.5" />
|
|
@@ -54,7 +60,7 @@
|
|
|
<param name="laser_lambda_short" value="0.1"/>
|
|
|
<param name="laser_model_type" value="likelihood_field"/>
|
|
|
<param name="laser_model_type" value="beam"/>
|
|
|
- <param name="laser_min_range" value="0.14"/>
|
|
|
+ <param name="laser_min_range" value="0.12"/>
|
|
|
<param name="laser_max_range" value="7.0"/>
|
|
|
<param name="laser_likelihood_max_dist" value="2.0"/>
|
|
|
<param name="update_min_d" value="0.05"/>
|
|
@@ -65,6 +71,6 @@
|
|
|
<param name="recovery_alpha_fast" value="0.1"/>
|
|
|
</node>
|
|
|
|
|
|
- <!-- startup view_navigation.launch -->
|
|
|
+ <!--(6) startup view_navigation.launch -->
|
|
|
<include file="$(find robot_navigation)/launch/view_navigation.launch" />
|
|
|
</launch>
|