使用Ubuntu22.04-Humble调试navigation2时发现Amcl节点有报错。现备份一个解决办法,希望也能帮到正在开发NAV2的朋友~
问题复现
复现步骤为
1、启动导航:
export TURTLEBOT3_MODEL=waffle
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py
export TURTLEBOT3_MODEL=waffle
ros2 launch rtabmap_ros turtlebot3_scan.launch.py
ros2 launch nav2_bringup bringup_launch.py map:=<full_path_to_your_map_name.yaml> open_rviz:=true
在运行第三条指令时终端出现报错:
Original error: According to the loaded plugin descriptions the class DifferentialMotionModel with base class type nav2_amcl::MotionModel does not exist. Declared types are nav2_amcl::DifferentialMotionModel nav2_amcl::OmniMotionModel
解决办法
解决办法为:
确认参数文件
打开bringup_launch.py源码,(我这里的navigation2_humble是源码编译的,所以源码路径为~/ros2_ws/src/navigation2_humble/nav2_bringup/bringup_launch.py),找到params_file参数,这里可以确认调用的参数为nav2_bringup功能包中的params路径下的nav2_params.yaml文件。
修改参数文件
参数文件中,amcl节点使用的robot_model_type参数值为"differential",需要修改为"nav2_amcl::DifferentialMotionModel",如下所示
amcl:
ros__parameters:
use_sim_time: True
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
#robot_model_type: "differential" #修改前
robot_model_type: "nav2_amcl::DifferentialMotionModel"#修改后
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan
修改后在工作空间编译nav2_bringup功能包后即可正常启动NAV2
colcon build --packages-select nav2_bringup