-
Notifications
You must be signed in to change notification settings - Fork 16
/
amcl.launch
executable file
·64 lines (59 loc) · 8.04 KB
/
amcl.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="robot_initial_x" default="0.0" />
<arg name="robot_initial_y" default="0.0" />
<arg name="robot_initial_yaw" default="0.0" />
<arg name="laser_scan_topic" default="scan" />
<arg name="map_frame_id" default="map" />
<arg name="odom_frame_id" default="odom" />
<arg name="base_link_frame_id" default="base_link" />
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Subscribed Topics -->
<remap from="scan" to="$(arg laser_scan_topic)" />
<!-- Overall filter parameters -->
<param name="min_particles" type="int" value="1000" /> <!-- default: 100 | Minimum allowed number of particles -->
<param name="max_particles" type="int" value="5000" /> <!-- default: 5000 | Maximum allowed number of particles -->
<param name="kld_err" type="double" value="0.05" /> <!-- default: 0.01 | Maximum error between the true distribution and the estimated distribution -->
<param name="kld_z" type="double" value="0.99" /> <!-- default: 0.99 | Upper standard normal quantile for (1 - p), where p is the probability that the error on the estimated distribution will be less than kld_err -->
<param name="update_min_d" type="double" value="0.1" /> <!-- default: 0.2 meters | Translational movement required before performing a filter update -->
<param name="update_min_a" type="double" value="0.25" /> <!-- default: π/6.0 radians | Rotational movement required before performing a filter update -->
<param name="resample_interval" type="int" value="1" /> <!-- default: 2 | Number of filter updates required before resampling -->
<param name="transform_tolerance" type="double" value="0.2" /> <!-- default: 0.1 seconds | Time with which to post-date the transform that is published, to indicate that this transform is valid into the future -->
<param name="recovery_alpha_slow" type="double" value="0.0" /> <!-- default: 0.0 (disabled) | Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.001 -->
<param name="recovery_alpha_fast" type="double" value="0.0" /> <!-- default: 0.0 (disabled) | Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.1 -->
<param name="initial_pose_x" type="double" value="$(arg robot_initial_x)" /> <!-- default: 0.0 meters | Initial pose mean (x), used to initialize filter with Gaussian distribution -->
<param name="initial_pose_y" type="double" value="$(arg robot_initial_y)" /> <!-- default: 0.0 meters | Initial pose mean (y), used to initialize filter with Gaussian distribution -->
<param name="initial_pose_a" type="double" value="$(arg robot_initial_yaw)" /> <!-- default: 0.0 radians | Initial pose mean (yaw), used to initialize filter with Gaussian distribution -->
<param name="initial_cov_xx" type="double" value="0.001" /> <!-- default: 0.5*0.5 meters | Initial pose covariance (x*x), used to initialize filter with Gaussian distribution -->
<param name="initial_cov_yy" type="double" value="0.001" /> <!-- default: 0.5*0.5 meters | Initial pose covariance (y*y), used to initialize filter with Gaussian distribution -->
<param name="initial_cov_aa" type="double" value="0.005" /> <!-- default: (π/12)*(π/12) radian | Initial pose covariance (yaw*yaw), used to initialize filter with Gaussian distribution -->
<param name="gui_publish_rate" type="double" value="10.0" /> <!-- default: -1.0 Hz | Maximum rate (Hz) at which scans and paths are published for visualization, -1.0 to disable -->
<param name="save_pose_rate" type="double" value="-1.0" /> <!-- default: 0.5 Hz | Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used on subsequent runs to initialize the filter. -1.0 to disable -->
<param name="use_map_topic" type="bool" value="true" /> <!-- default: false | When set to true, AMCL will subscribe to the map topic rather than making a service call to receive its map -->
<param name="first_map_only" type="bool" value="false" /> <!-- default: false | When set to true, AMCL will only use the first map it subscribes to, rather than updating each time a new one is received -->
<!-- Laser model parameters -->
<param name="laser_min_range" type="double" value="-1.0" /> <!-- default: -1.0 | Minimum scan range to be considered; -1.0 will cause the laser's reported minimum range to be used -->
<param name="laser_max_range" type="double" value="-1.0" /> <!-- default: -1.0 | Maximum scan range to be considered; -1.0 will cause the laser's reported maximum range to be used -->
<param name="laser_max_beams" type="int" value="100" /> <!-- default: 30 | How many evenly-spaced beams in each scan to be used when updating the filter -->
<param name="laser_z_hit" type="double" value="0.6" /> <!-- default: 0.95 | Mixture weight for the z_hit part of the model -->
<param name="laser_z_short" type="double" value="0.05" /> <!-- default: 0.1 | Mixture weight for the z_short part of the model -->
<param name="laser_z_max" type="double" value="0.05" /> <!-- default: 0.05 | Mixture weight for the z_max part of the model -->
<param name="laser_z_rand" type="double" value="0.3" /> <!-- default: 0.05 | Mixture weight for the z_rand part of the model -->
<param name="laser_sigma_hit" type="double" value="0.2" /> <!-- default: 0.2 meters | Standard deviation for Gaussian model used in z_hit part of the model -->
<param name="laser_lambda_short" type="double" value="0.1" /> <!-- default: 0.1 | Exponential decay parameter for z_short part of model -->
<param name="laser_likelihood_max_dist" type="double" value="2.0" /> <!-- default: 2.0 meters | Maximum distance to do obstacle inflation on map, for use in likelihood_field model -->
<param name="laser_model_type" type="str" value="likelihood_field" /> <!-- default: "likelihood_field" | Which model to use, either beam, likelihood_field, or likelihood_field_prob -->
<!-- Odometry model parameters -->
<param name="odom_model_type" type="str" value="diff" /> <!-- default: "diff" | Which model to use, either diff or omni -->
<param name="odom_alpha1" type="double" value="0.5" /> <!-- default: 0.2 | Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion -->
<param name="odom_alpha2" type="double" value="0.5" /> <!-- default: 0.2 | Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion -->
<param name="odom_alpha3" type="double" value="0.8" /> <!-- default: 0.2 | Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion -->
<param name="odom_alpha4" type="double" value="0.5" /> <!-- default: 0.2 | Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion -->
<param name="odom_alpha5" type="double" value="0.2" /> <!-- default: 0.2 | Translation-related noise parameter (only used if model is "omni") -->
<param name="odom_frame_id" type="str" value="$(arg odom_frame_id)" /> <!-- default: "odom" | Which frame to use for odometry -->
<param name="base_frame_id" type="str" value="$(arg base_link_frame_id)" /> <!-- default: "base_link" | Which frame to use for the robot base -->
<param name="global_frame_id" type="str" value="$(arg map_frame_id)" /> <!-- default: "map" | The name of the coordinate frame published by the localization system -->
</node>
</launch>
<!-- https://github.com/ros-planning/navigation/blob/indigo-devel/amcl/examples/amcl_diff.launch -->
<!-- https://github.com/turtlebot/turtlebot_apps/blob/indigo/turtlebot_navigation/launch/includes/amcl.launch.xml -->