Wiki

Note: This tutorial assumes that you have completed the previous tutorials: navigation/Tutorials/RobotSetup.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Basic Navigation Tuning Guide

Description: This guide seeks to give some standard advice on how to tune the ROS Navigation Stack on a robot. This guide is in no way comprehensive, but should give some insight into the process. I'd also encourage folks to make sure they've read the ROS Navigation Tutorial before this post as it gives a good overview on setting the navigation stack up on a robot wheras this guide just gives advice on the process.

Tutorial Level: INTERMEDIATE

Is the robot navigation ready?

The large majority of the problems I run into when tuning the navigation stack on a new robot lie in areas outside of tuning parameters on the local planner. Things are often wrong with the odometry of the robot, localization, sensors, and other pre-requisites for running navigation effectively. So, the first thing I do is to make sure that the robot itself is navigation ready. This consists of three component checks: range sensors, odometry, and localization.

Range Sensors

If the robot isn't getting information from its range sensors, such as lasers, then nothing with navigation will work. I'll make sure that I can view sensor information in rviz, that it looks relatively correct, and that its coming in at the expected rate.

Odometry

Often, I'll have a lot of trouble getting a robot to localize correctly. It will constantly get lost and I'll spend a lot of time mucking with the parameters for AMCL only to find that the real culprit is the robot's odometry. As such, I always run two sanity checks to make sure that I believe the odometry of a robot.

The first test checks how reasonable the odometry is for rotation. I open up rviz, set the frame to "odom," display the laser scan the robot provides, set the decay time on that topic high (something like 20 seconds), and perform an in-place rotation. Then, I look at how closely the scans match each other on subsequent rotations. Ideally, the scans will fall right on top of each other, but some rotational drift is expected, so I just make sure that the scans aren't off by more than a degree or two.

The next test is a sanity check on odometry for translation. I'll set up rviz the same way with the robot a few meters away from a wall. Then, I'll drive the robot straight at the wall and look at the thickness of the wall as reported by the aggregated laser scans in rviz. Ideally, the wall should look like a single scan but I just make sure that it doesn't have a thickness of more than a few centimeters. If you drive a meter towards a wall and get scans spread out over half a meter though, something is likely wrong with the odometry.

Localization

Assuming that both odometry and a laser scanner are performing reasonably, making a map and tuning AMCL normally isn't too bad. First, I'll run either gmapping or karto and joystick the robot around to generate a map. Then, I'll use that map with AMCL and make sure that the robot stays localized. If the odometry for the robot that I'm running on isn't very good, I'll play around a bit with the odometry model parameters for AMCL. A good test for the whole system is to make sure that laser scans and the map can be visualized in the "map" frame in rviz and that the laser scans match up well with the map of the enviroment. I also always make sure to set the initialpose for the robot in rviz with reasonable accuracy before expecting things to work.

The Costmap

Once I'm satisfied that the robot satisfies the prerequisites for navigation, I like to make sure that the costmap is setup and configured properly. I'll leave details on how to configure things for the costmap to the ROS Navigation Tutorial and costmap_2d documentation, but I'll give some tips on the things that I often do. Some things that I find useful for tuning the costmap:

The Local Planner

If I'm satisfied that things up through the costmap are behaving satisfactorily, I'll move on to tuning parameters for the local planner. On robots that have reasonable acceleration limits, I typically use the dwa_local_planner, on those that have lower acceleration limits and would benefit from a rollout that takes acceleration limits into account at every step, I'll use the base_local_planner . Tuning the dwa_local_planner is more pleasant than tuning the base_local_planner because its parameters are dynamically_reconfigurable, though adding dynamic_reconfigure across the board for the navigation stack is on the roadmap. Ok, on to tips for the planners:

ROS Navigation Tuning Guide

If your robot is navigation ready, and you are about to go through the process of optimizing the navigation behavior for your robot, here is a ROS Navigation Tuning Guide, created by Kaiyu Zheng. It discusses components including setting velocity and acceleration, global planner, local planner (specifically DWA Local Planner), costmap, AMCL (briefly), recovery behaviors, etc. Here is a video demo for the improvement of navigation system on the SCITOS G5 robot, based on ideas presented in this guide. This guide is in no way perfect and complete (e.g. AMCL section needs more discussion), and may contain errors. Feel free to file an issue or pull request to this Github Repository https://github.com/zkytony/ROSNavigationGuide, and contribute to it!


CategoryCategory

Wiki: navigation/Tutorials/Navigation Tuning Guide (last edited 2018-12-10 02:16:49 by KaiyuZheng)