AMR_T800/Controllers/Packages/amr_startup/launch/includes/amcl.launch
2026-01-07 09:28:55 +07:00

106 lines
6.0 KiB
XML

<?xml version="1.0" ?>
<launch>
<arg name="tf_prefix" default="" />
<arg name="namespace" default="$(arg tf_prefix)" doc="Namespace to push all topics into."/>
<arg name="use_map_topic" default="true"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_topic" default="/map"/> <!-- if use_map_topic = true -->
<arg name="map_service" default="/static_map"/> <!-- if use_map_topic = false -->
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>
<arg name="odom_frame_id" default="$(arg tf_prefix)/odom"/>
<arg name="base_frame_id" default="$(arg tf_prefix)/base_footprint"/>
<arg name="global_frame_id" default="/map"/>
<group if="$(eval namespace != '')" ns="$(arg namespace)">
<node pkg="amcl" type="amcl" name="amcl" output="screen" >
<param name="use_map_topic" value="$(arg use_map_topic)"/>
<param name="odom_model_type" value="diff-corrected"/>
<param name="gui_publish_rate" value="10.0"/>
<param name="save_pose_rate" value="0.5"/>
<param name="laser_max_beams" value="200"/>
<param name="laser_min_range" value="-1.0"/>
<param name="laser_max_range" value="-1.0"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.09"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.02"/>
<param name="odom_alpha2" value="0.01"/>
<param name="odom_alpha3" value="0.01"/>
<param name="odom_alpha4" value="0.02"/>
<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_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.2"/>
<param name="odom_frame_id" value="$(arg odom_frame_id)"/>
<param name="base_frame_id" value="$(arg base_frame_id)"/>
<param name="global_frame_id" value="$(arg global_frame_id)"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.2"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<remap from="scan" to="$(arg scan_topic)"/>
<remap from="map" to="$(arg map_topic)"/>
<remap from="static_map" to="$(arg map_service)"/>
</node>
</group>
<!-- Duplicate of the above in case namespace is empty. This is necessary to
avoid the "<group> tag has an empty 'ns' attribute" parsing error. -->
<group unless="$(eval namespace != '')">
<node pkg="amcl" type="amcl" name="amcl" output="screen" >
<param name="use_map_topic" value="$(arg use_map_topic)"/>
<param name="odom_model_type" value="diff-corrected"/>
<param name="gui_publish_rate" value="10.0"/>
<param name="save_pose_rate" value="0.5"/>
<param name="laser_max_beams" value="200"/>
<param name="laser_min_range" value="-1.0"/>
<param name="laser_max_range" value="-1.0"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.09"/>
<param name="kld_z" value="0.99"/>
<param name="odom_alpha1" value="0.02"/>
<param name="odom_alpha2" value="0.01"/>
<param name="odom_alpha3" value="0.01"/>
<param name="odom_alpha4" value="0.02"/>
<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_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.2"/>
<param name="odom_frame_id" value="$(arg odom_frame_id)"/>
<param name="base_frame_id" value="$(arg base_frame_id)"/>
<param name="global_frame_id" value="$(arg global_frame_id)"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.2"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<remap from="scan" to="$(arg scan_topic)"/>
<remap from="map" to="$(arg map_topic)"/>
<remap from="static_map" to="$(arg map_service)"/>
</node>
</group>
</launch>