[Documentation] [TitleIndex] [WordIndex

Is My Odometry Good Enough for AMCL

Problem: The robot doesn't seem to be localized properly. Its position estimate jumps around a lot in rviz and the navigation stack doesn't seem able to follow the plans produced by the global planner. Is this a problem with AMCL or my robot's odometry.

Solution: There are a couple of tests that are helpful to run to see how good the odometry of a robot is:

Missing Obstacles in Costmap2D

Problem: Obstacles don't show up from my planar laser in the costmap. I've checked that topics are connected to the move_base node in the way that I expect, but I still can't get anything to show up.

Solution: This often occurs because the transform from laser->base_link of your robot does not account for the height of the laser. There are two solutions to this problem. The first, and recommended, solution is to modify the transform to publish the laser's height. The second, and quicker, solution is to set the min_obstacle_height parameter (see costmap_2d documentation) to be 0.0cm.

Segway RMP*

Problem: I recently switched our robot (a Segway RMP50) from using wavefront to the new move_base system. For the most part, it's working great, but occasionally the robot will be executing a plan and drive near an obstacle, and it will stop and wait indefinitely. It will be close to the obstacle but not in danger of hitting it. If I nudge the robot forward with the joystick, it will then continue to its destination.

Can anyone explain what might be going on and point me to the right parameters to adjust so that it doesn't get stuck?

Solution: One solution is to enforce minimum linear and angular velocities in the segway driver: once the linear and/or angular velocity leaves a deadband, kick it up to whatever velocity is necessary to get the robot to move. Otherwise move_base might command a (very small) velocity that causes the robot to just sit there, stalled.

Probably not the most elegant solution, but it seems to work.

The relevant parameters to tweak in move_base are:

tf Warning

Problem: I'm trying to run the navigation stack, but am getting the following tf warning every 10 seconds:

1254003703.027025000 WARN
[~/ros/pkgs/geometry/tf/src/tf.cpp:169(Transformer::setTransform)
[topics: /rosout, /cmd_vel, /visualization_marker,
/move_base/current_position, /move_base/goal] TF_OLD_DATA ignoring
data from the past for frame /base_link at time 1.254e+09 according to
authority /tf_utm0_broadcaster
Possible reasons are listed at

Solution: This error occurs when tf recieves data which is older than the data in it's cache. I expect that in your system /tf_utm0_broadcaster is broadcasting with an old/incorrect timestamp. Another possible explanation is that the system clocks of the computers you are running on are not synchronized.

The error message is partially explained at http://wiki/tf/Errors_explained

Try running the script view_frames in the tf package and make sure that you have a connected tree. I'd also suggest running roswtf to see if it flags any errors.

tf Error

Problem: I get the following tf error when trying to run the navigation stack:

[ERROR] 1254158042.234182000: Connectivity Error: No Common Parent
Case C between /base_link and /odom
Frame /base_link exists with parent /frameid_utm0.
Frame /odom exists with parent NO_PARENT.
Frame /frameid_utm0 exists with parent NO_PARENT.

1 forward length with /frameid_utm0
When trying to transform between /base_link and /odom.

Solution: tf does not allow multiple parents for a node in its transform tree so make sure that each node in your tf transform tree has only one parent. In this case, frameid_utm is being published as the parent of base_link, but odom is also being published as the parent of base_link. This means that two frames are fighting to parent base_link, resulting in the error above. For future reference, the roswtf tool will warn if it detects multiple publishers fighting for the parent of a single link.

Costmap2DROS Warning

Problem: When attempting to run the navigation stack, I recieve the following warning repeatedly:

1254003704.325349000 INFO
[/home/advait/ros/pkgs/navigation/costmap_2d/src/costmap_2d_ros.cpp:193(Costmap2DROS::Costmap2DROS)
[topics: /rosout, /cmd_vel, /visualization_marker,
/move_base/current_position, /move_base/goal] Request failed; trying
again...

Solution: This means that the navigation stack has been configured to use a map, but one has not been advertised on the "/map" service. Check to make sure that you are launching the map_server correctly or configure the navigation stack to operate in an odometric coordinate frame.

Weird Rotational Behavior

Problem: Sometimes, the robot will perform a small rotation to one side followed by a large rotation in the other direction just to turn around.

Solution: This problem is caused by scoring in-place rotations by their endpoint (see the base_local_planner package for details on scoring). The robot decides to rotate to the left, but since it forward simulates each rotational trajectory for a second or so, a fast rotation to the right scores more favorably because it ends closer to the robot's goal orientation. Once the robot decides to go right instead, it will have to commit to that rotation because it is not allowed to oscillate betweeen counterclockwise and clockwise rotations, and this results in it eventually achieving its desired pose. This may be fixed down the road by forward simulating in-place rotations differently than other trajectories considered, but its not a pressing enough issue for us to solve right now.


2024-03-23 12:47