49 lines
2.2 KiB
XML
49 lines
2.2 KiB
XML
<?xml version="1.0" ?>
|
|
<launch>
|
|
<param name="/use_sim_time" value="true"/>
|
|
<node name="rosbag" pkg="rosbag" type="play"
|
|
args="-s 0.0 -d 5 -r 1 --clock --hz 10 $(find amcl)/test/small_loop_prf_indexed.bag"/>
|
|
<node name="map_server" pkg="map_server" type="map_server" args="$(find amcl)/test/willow-full.pgm 0.1"/>
|
|
<node pkg="amcl" type="amcl" name="amcl" respawn="false" output="screen">
|
|
<remap from="scan" to="base_scan" />
|
|
<param name="transform_tolerance" value="0.2" />
|
|
<param name="gui_publish_rate" value="10.0"/>
|
|
<param name="save_pose_rate" value="0.5"/>
|
|
<param name="laser_max_beams" value="30"/>
|
|
<param name="min_particles" value="500"/>
|
|
<param name="max_particles" value="5000"/>
|
|
<param name="kld_err" value="0.05"/>
|
|
<param name="kld_z" value="0.99"/>
|
|
|
|
<param name="odom_model_type" value="omni"/>
|
|
<param name="odom_alpha1" value="0.2"/>
|
|
<param name="odom_alpha2" value="0.2"/>
|
|
<param name="odom_alpha3" value="0.8"/>
|
|
<param name="odom_alpha4" value="0.2"/>
|
|
<param name="odom_alpha5" value="0.1"/>
|
|
|
|
<param name="laser_z_hit" value="0.5"/>
|
|
<param name="laser_z_short" value="0.05"/>
|
|
<param name="laser_z_max" value="0.05"/>
|
|
<param name="laser_z_rand" value="0.5"/>
|
|
<param name="laser_sigma_hit" value="0.2"/>
|
|
<param name="laser_lambda_short" value="0.1"/>
|
|
<param name="laser_lambda_short" value="0.1"/>
|
|
<param name="laser_model_type" value="likelihood_field"/>
|
|
<param name="laser_likelihood_max_dist" value="2.0"/>
|
|
|
|
<param name="update_min_d" value="0.2"/>
|
|
<param name="update_min_a" value="0.5"/>
|
|
<param name="odom_frame_id" value="odom_combined"/>
|
|
<param name="resample_interval" value="1"/>
|
|
<param name="transform_tolerance" value="0.1"/>
|
|
<param name="recovery_alpha_slow" value="0.0"/>
|
|
<param name="recovery_alpha_fast" value="0.0"/>
|
|
<param name="initial_pose_x" value="14.099"/>
|
|
<param name="initial_pose_y" value="21.063"/>
|
|
<param name="initial_pose_a" value="-0.006"/>
|
|
</node>
|
|
<test time-limit="180" test-name="basic_localization_small_loop_prf" pkg="amcl"
|
|
type="basic_localization.py" args="0 13.94 23.02 4.72 0.75 0.75 66.0"/>
|
|
</launch>
|