Skip to content
Snippets Groups Projects
Commit 31291566 authored by Jiaao Liu's avatar Jiaao Liu
Browse files

add amcl

parent 31e3121c
No related branches found
No related tags found
No related merge requests found
<launch>
<!-- 启动 map_server 以发布地图 -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find asclinic_pkg)/maps/map.yaml" />
<!-- 静态 TF 变换: base_link 到 laser -->
<node pkg="tf2_ros" type="static_transform_publisher" name="base_to_laser" args="0 0 1 0 0 0 base_link laser" />
<!-- 静态 TF 变换: odom 到 base_link -->
<node pkg="tf2_ros" type="static_transform_publisher" name="odom_to_base" args="0 0 0 0 0 0 odom base_link" />
<!-- 启动 AMCL 节点 -->
<node name="amcl" pkg="amcl" type="amcl" output="screen">
<param name="use_map_topic" value="true" />
<param name="odom_frame_id" value="odom" />
<param name="base_frame_id" value="base_link" />
<param name="global_frame_id" value="map" />
<param name="scan_topic" value="/asc/scan" />
<rosparam file="$(find asclinic_pkg)/param/amcl_params.yaml" command="load" />
</node>
<!-- 启动 RViz -->
<node name="rviz" pkg="rviz" type="rviz" />
</launch>
......@@ -20,7 +20,7 @@
<param name="ymin" value="-3.0"/>
<param name="xmax" value="3.0"/>
<param name="ymax" value="3.0"/>
<param name="maxUrange" value="8.0"/>
<param name="maxUrange" value="3.0"/>
<param name="maxRange" value="8.0"/>
<remap from="scan" to="/asc/scan"/>
</node>
......
123
\ No newline at end of file
# AMCL parameters
min_particles: 500
max_particles: 2000
kld_err: 0.05
kld_z: 0.99
update_min_d: 0.2
update_min_a: 0.2
resample_interval: 1
transform_tolerance: 0.5
# Motion model parameters
recovery_alpha_slow: 0.1
recovery_alpha_fast: 0.1
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.1
# Laser model parameters
laser_min_range: 0.1
laser_max_range: 3
laser_max_beams: 60
laser_z_hit: 0.95
laser_z_short: 0.1
laser_z_max: 0.05
laser_z_rand: 0.05
laser_sigma_hit: 0.2
laser_lambda_short: 0.1
# Odometry model parameters
odom_alpha1: 0.2
odom_alpha2: 0.2
odom_alpha3: 0.2
odom_alpha4: 0.2
odom_alpha5: 0.1
# Initial pose estimation
init_pose_x: 0.0
init_pose_y: 0.0
init_pose_a: 0.0
init_cov_xx: 0.5
init_cov_yy: 0.5
init_cov_aa: 0.1
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment