Skip to content

Commit

Permalink
Slightly improved AMCL params
Browse files Browse the repository at this point in the history
  • Loading branch information
lalten committed Jan 28, 2016
1 parent ada7b46 commit c7fde93
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
2 changes: 1 addition & 1 deletion tas/launch/odom.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
laserscan_topics: /scan_front /scan_back
angle_min: -3.14159
angle_max: 3.14159
range_min: 0
range_min: 0.3
range_max: 100
</rosparam>
</node>
Expand Down
6 changes: 4 additions & 2 deletions tas/launch/odom_amcl.launch
Original file line number Diff line number Diff line change
Expand Up @@ -54,10 +54,12 @@
<rosparam>
update_min_d: 0.0 # Translational movement required before performing a filter update. (default 0.2)
update_min_a: 0.0 # Translational movement required before performing a filter update. (default π/6.0=0.523598776 radians)
min_particles: 800
max_particles: 8000
odom_model_type: diff
odom_alpha1: 0.5 # expected noise in odometry rotation from rotational robot motion (default 0.2)
odom_alpha2: 0.4 # expected noise in odometry rotation from translational robot motion (default 0.2)
odom_alpha3: 2.0 # expected noise in odometry translation from translational robot motion (default 0.2)
odom_alpha2: 0.8 # expected noise in odometry rotation from translational robot motion (default 0.2)
odom_alpha3: 2.5 # expected noise in odometry translation from translational robot motion (default 0.2)
odom_alpha4: 0.2 # expected noise in odometry translation from rotational robot motion (default 0.2)
odom_alpha5: 0.2 # Translation-related noise parameter (default 0.2)
tf_broadcast: true # allow amcl to publish the transform between the global frame and the odometry frame
Expand Down

0 comments on commit c7fde93

Please sign in to comment.