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:

  • Make sure to set the expected_update_rate parameter for each observation source based on the rate at which the sensor actually publishes. I normally give a fair amount of tolerance here, putting the period for the check at twice what I'd expect, but its nice to receive warnings from navigation when a sensor falls way below its expected rate.

  • Set the transform_tolerance parameter appropriately for the system. Its nice to check what the expected latency is for a transform from the "base_link" frame to the "map" frame using tf. I typically use tf_monitor to look at the delay for the system and set the parameter conservatively off of that. Also, if the delay reported by tf_monitor is sufficiently large, I might poke around a bit to see what's causing the latency. This sometimes leads me to find issues with how transforms are being published for a given robot.

  • On robots that lack processing power, I'll consider turning down the map_update_rate parameter. When doing this, however, I take into account the fact that this will cause a delay in how quickly sensor data makes it into the costmap which, in turn, slows the speed at which the robot reacts to obstacles.

  • The publish_frequency parameter is useful for visualizing the costmap in rviz. However, especially for large global maps, the parameter can cause things to run slowly. In production systems, I consider turning down the rate at which the costmap is published and when I need to visualize very large maps, I make sure to set the rate really low.

  • The decision on whether to use the voxel_grid or costmap model for the costmap depends largely on the sensor suite that the robot has. Tuning the costmap for a 3D-based costmap is more involved as considerations about unknown space really come into play. If the robot I'm using just has a planar laser, I always use the costmap model for the map.

  • Sometimes, its useful to be able to run navigation solely in the odometric frame. To do this, I find the easiest thing to do is to copy my local_costmap_params.yaml file over my global_costmap_params.yaml file and change the the width and height of the map to be something more like 10 meters. This is a really easy way to get things up and running if you want to tune navigation independent of localization performance.

  • I tend to pick the resolution of the maps that I'm using based on the robot's size and processing ability. On a robot that has a lot of processing power and needs to fit through narrow spaces, like the PR2, I'll use a fine-grained map... setting the resolution to something like 0.025 meters. For something like a roomba, I might go as high as 0.1 meters in resolution to reduce the computational load.
  • Rviz is a great way to verify that the costmap is working correctly. I typically view the obstacle data from the costmap and make sure that it lines up with both the map and laser scans as I drive the robot around under joystick control. This is a sanity check that sensor data is making it into the costmap in a reasonable way. If I've decided to track unknown space with a robot, mostly these are robots that are using the voxel_grid model for the costmap, I make sure to look at the unknown space visualization to see that unknown space is being cleared out in a reasonable way. A good check I do to see if obstacles are being cleared out correctly from the costmap is to simply walk in front of the robot and see if it both successfully sees me and clears me out. For details on the topics published by the costmap to rviz, check out the navigation with rviz tutorial.

  • Its a good idea to check the system load when the navigation stack is running only the costmap. This means bringing up the move_base node, but not sending it a goal and looking at load. If the computer is bogged down at this point, I know I need to make some CPU saving parameter tweaks if I want any chance of running the planners.

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:

  • The most important thing for both planners is that the acceleration limit parameters are set correctly for a given robot. If these parameters are off, I'd expect sub-optimal behavior from a robot. If I don't know what the acceleration limits of a robot are, I'll take the time to write a script that commands max translational and rotational velocity to the motors for some period of time, look at the reported velocity from odometry (assuming the odometry gives a reasonable estimate of this), and derive the acceleration limits from that. Setting these parameters reasonably often saves me a lot of time later.
  • If the robot I'm working with has low acceleration limits, I make sure that I'm running the base_local_planner with dwa set to false. After setting dwa to true, I'll also make sure to update the vx_samples parameter to something between 8 and 15 depending on the processing power available. This will allow for non-circular curves to be generated in the rollout.

  • If localization for the robot I'm working with isn't great, I'll make sure to set the goal tolerance parameters a bit higher than I would otherwise. I'll also up the rotational tolerance if the robot has a high minimum rotational velocity to avoid oscillations at the goal point.
  • If I'm using a low resolution for CPU reasons, I'll sometimes up the sim_granularity parameter a bit to save some cycles.

  • I actually rarely find myself changing the path_distance_bias and goal_distance_bias (for base_local_planner these parameters are called pdist_scale and gdist_scale) parameters on the planners very much. When I do, its normally because I'm trying to restrict the freedom of the local planner to leave the planned path to work with a global planner other than NavFn. Turning the path_distance_bias parameter up, will make the robot follow the path more closely at the expense of moving towards the goal quickly. If this weight is set too high, the robot will refuse to move because the cost of moving is greater than staying at its location on the path.

  • If I want to reason about the cost function in an intelligent way, I'll make sure to set the meter_scoring parameter to true. This makes it so distances in the cost function are in meters instead of cells and also means that I can tune the cost function for one map resolution and expect reasonable behavior when I move to others. Furthermore, you can now visualize the cost function produced by the local planner in rviz by setting the publish_cost_grid parameter to true. (This somehow never made it into the docs, I'll get to that sometime soon). Given the cost function in meters, I can compute the tradeoff in cost of moving 1 meter towards the goal balanced against how far away I am from the planned path. This tends to give me a decent idea of how to tune things.

  • Trajectories are scored from their endpoints. This means that setting the sim_time parameter to different values can have a large affect on how the robot behaves. I normally set this parameter to between 1-2 seconds, where setting it higher can result in slightly smoother trajectories, making sure that the minimum velocity multiplied by the sim_period is less than twice my tolerance on a goal. Otherwise, the robot will prefer to rotate in place just outside of range of its target position rather than moving towards the goal.

  • Accurate trajectory simulation also depends on having reasonable velocity estimates from odometry. This comes from the fact that both the dwa_local_planner and base_local_planner use this velocity estimate, along with the acceleration limits of the robot, to determine the feasible velocity space for a planning cycle. Though the velocity estimate coming from odometry doesn't have to be perfect, it is important to make sure that its at least close to get optimal behavior.

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)