Introduction to the ROS Navigation Stack
Table of Contents
1 Introduction
The navigation "stack" (it's actually a meta-package) is meant to allow easy 2-dimensional navigation for arbitrary mobile robots. Conceptually, the navigation stack uses information from a variety of sensor streams and outputs velocity commands to control a mobile robot to move collision-free through the world.
This stack is highly configurable. It can handle a variety of sensor sources, it works for both holonomic and nonholonomic platforms, it works with arbitrary robot footprints, and can even handle footprints changing with time (imagine you have an arm attached to your robot).
1.1 High level conceptual overview
Generically, there are several parts that are required for the navstack to function properly:
- Global and local costmaps These are how the navstack represents the world. The global costmap is generally used to represent the large-scale environment that the robot is operating in, and the local costmap is used for obstacle avoidance while moving. These costmaps are basically a grid of cells that specify whether each cell is occupied, free, or unknown.
- Base controller This node must subscribe to a
geometry_msgs/Twist
message (by default this message is on thecmd_vel
topic), and somehow move your robot. This is the node that is responsible for moving the robot based on the output of the navstack. - Odometry source The navstack requires odometry information for your
robot. So something must publish a
nav_msgs/Odometry
message that provides your robot's own dead-reckoning estimate of its current pose and velocity in an odometry frame. Additionally, something must provide thetf
transform from an odometry frame to the base of the robot. Often all of this information is provided by the base controller node. - Sensing system There needs to be some mechanism for detecting obstacles in
the world and adding them to the costmaps. Typically these are either laser
scanners providing
sensor_msgs/LaserScan
messages or depth cameras providingsensor_msgs/PointCloud2
messages. Some implementations have used RGB cameras or even sonar sensors, although this is not the norm. - Global and local planners The global planner is responsible for using a planning algorithm to develop a collision-free path from the robot's current pose to a goal pose. The local planner then runs at a higher frequency and locally modifies the global plan to avoid collisions as the robot moves (typically these potential collisions are represented only in the local costmap and the global costmap only includes static, pre-known obstacles such as walls).
2 Important Packages
- amcl
- Stands for "Adaptive Monte Carlo Localization". This package
provides a node that uses a particle filter to provide an estimate of a
robot's pose within a static map. Typically this means that
amcl
will provide a transform from a/map
frame to a base frame attached to a robot. This node requires a static map provided by the map_server, and a laser scan. - costmap_2d
- This package creates 2D costmaps based on "occupancy grids". Essentially, this package uses different "layers" to build a 3D occupancy grid. Then based on a few different parameters it produces the 2D costmap that contains only one of three values "occupied", "free" or "unknown". The most common layers are the "static map" layer, the "obstacle map" layer, and the "inflation layer".
- dwa_local_planner
- This is the default local planner used by the navstack.
DWA stands for Dynamic Window Approach. This local planner works by
essentially sampling the space of possible controls for a robot at a
given pose and time. For each sample, it integrates the kinematics of the
robot forward for a short duration to predict a short trajectory that
represents what would happen if the robot were to follow the sampled
control for this short duration. Then for each sampled trajectory, the
planner calculates a performance score that balances things like distance
to obstacles, distance to the global plan, and distance to local goal.
Assuming the best-scoring set of controls are obstacle free, it then
provides these controls to
move_base
through thenav_core::BaseLocalPlanner
interface. - global_planner
- This package uses standard planning algorithms to plan
global plans in the global costmap. It can plan using things like
Dijkstra's algorithm, or A*. It is responsible for providing a
nav_msgs/Path
to themove_base
package. - gmapping
- This node can be used for generating static maps using SLAM. As
you drive around, a map is built and continually updated using odometry
information and sensor data (laser scans or point clouds). Once you are
satisfied with the map, you can use the
map_server
package'smap_saver
node to save the map itself as an image, and the map metadata as a YAML file. - map_server
- This package provides two nodes.
map_server
offers up map data as a ROS service so that nodes requiring map data can request it.map_saver
can be used to save maps and map metadata to disk. - move_base
- This node provides an action interface that works with both a
global and local planner to attempt drive a mobile base from it's current
pose to a goal pose. It is probably the most important part of the
navstack as it works with planners, costmaps, odometry information, and
localization information all at once. In a typical navstack
implementation, many YAML files are used to set parameters for planners,
costmaps, robot configurations, etc. and then the
move_base
note is initialized and it uses all of these parameters. - nav_core
- This is the package that provides the definitions of common
software interfaces for
BaseGlobalPlanner
,BaseLocalPlanner
, andRecoveryBehavior
. This package is what allows people to write their own planners and use them instead of the defaults. - robot_pose_ekf
- This node fuses partial pose estimates from a variety of different sensors to provide more reliable odometry information for use in the navstack. It can combine wheel odometry information, IMU sensors, and visual odometry information. It is not necessary to run the navstack, but many robots use it.
3 Related Packages
- carrot_planner
- This is a global planner that can be used for getting a robot as close to an obstacle as possible (useful if your goal pose is inside of an obstacle).
- eband_local_planner
- This is a local planner based on elastic band optimization.
- sbpl
- The
sbpl
package provides thesbpl_lattice_planner
as a global planner for the navstack. This planner is based on stitching together "motion primitives". - fake_localization
- This node is used to convert odometry information
into the information that would be provided by
amcl
. Mostly useful when trying to simulate the navstack. - voxel_grid
- This package provides an efficient 3D voxel grid. Basically, this allows you to use a full 3D sensor (Kinect, Lidar) and represent the detected obstacles using a special data structure called a voxel grid. Then this package provides very efficient ways to determine if the state of the cell under a given location in the voxel grid should be marked, free, or unknown.
- robot_localization
- Much like the
robot_pose_ekf
package, this package is for state estimation through sensor fusion. It is more modern, more actively developed, more flexible, and more powerful than therobot_pose_ekf
package. Someday, it will likely completely replacerobot_pose_ekf
. - hector_slam
- Based off of a paper titled A Flexible and Scalable SLAM System with Full 3D Motion Estimation, this is a very fast and robust alternative to
gmapping
. Inhector_slam
, a "navigation filter" is used to fuse data from relative pose estimation sensors (IMU, compass, GPS, altimeter, etc.) to provide a good seed for a 2D scan matching algorithm. With a properly tuned navigation filter, this package can nearly eliminate loop-closure issues. Check out this impressive video that shows someone walking around mapping an unknown environment using a hand-held scanner. Note that they also have a full YouTube playlist of examples of people usinghector_slam
. - googlecartographer_ros
- Google Cartographer is a modern, real-time SLAM
system for 2D and 3D that works across multiple platforms and sensor
configurations. Check out the announcement of the project on the Google
Open Source Blog. Recently, ROS support for this project was released via
the
googlecartographer_ros
package. Even though this is a new system, there are already people using this as part of the navstack. Check out this video from Google showing the results of 2D SLAM in the Deutsches Museum, or this video from Toyota Research Institute that shows a robot mapping and navigating in real-time in a highly dynamic environment. - rtabmap_ros
- Quoting from the ROS wiki: This package is a ROS wrapper of RTAB-Map (Real-Time Appearance-Based Mapping), a RGB-D SLAM approach based on a global loop closure detector with real-time constraints. This package can be used to generate a 3D point clouds of the environment and/or to create a 2D occupancy grid map for navigation. I've seen this package used quite often in recent years with much success.
- rgbdslam
- Through the history of ROS, this was one of the most widely used 3D SLAM implementations using an RGBD sensor (originally a Kinect). There are two versions of this software floating around the Wiki; V1 has been completely deprecated and V2 is what you should be using. This is most often used for 3D planning problems (not the navstack), but it is included here because it fits with the other SLAM implementations.
- laser_scan_matcher
- This is a simple tool that can provide odometry
estimates by estimating the transform between successive laser scans.
This can be used as part of a localization or SLAM system, as an input to
robot_localization
orrobot_pose_ekf
, or as a standalone odometry system. - dwb_local_planner
- This is a successor to
dwa_local_planner
. Designed to be much more flexible and extensible, while also being backwards compatible. David Lu gave a great talk at ROSCon 2017 about this package (video and slides). - move_base_flex
- Backwards compatible, yet much more powerful, replacement
for
move_base
. Wiki page not yet complete, check out the package on GitHub. Also see the ROSCon 2017 talk from Magazino (video and slides).
3.1 Recovery nodes
There are several packages that are part of the navstack that are used for
defining "recovery" behaviors. These nodes are compatible with the
RecoveryBehavior
API defined in nav_core
. These nodes can be called to
try and fix things going wrong with the navstack.
- clear_costmap_recovery This implements a simple recovery behavior that simply clears out costmaps (and reverts them to static data if it exists) for all data greater than some radius from the robot.
- move_slow_and_clear This recovery behavior involves clearing the costmap near the robot and then specifying strict velocity limits to make the robot move very slowly until the strict limits are removed.
- rotate_recovery This recovery behavior involves simply spinning in place to attempt to clear out the costmap using fresh laser data.
4 Resources
- David Lu's ROSCon 2014 Talk: Navigation illumination: Shedding light on the ROS navstack (PDF of his slides)
- ROS Navigation tutorials
- ROS Navigation YouTube video
- ROS with gmapping PiRobot Video
- IROS 2014 paper on the theory used in the layered costmaps of ROS navigation
- On the Wiki, the costmap_2d/hydro page contains a slightly different set of
information than the main costmap_2d page. Both are useful. Note that the name
costmap_2d/hydro
in the first link does not mean that the documentation is specific to ROS Hydro. Rather, this name is a relic leftover from the fact that the implementation of the costmaps in the navstack changed significantly with the Hydro release. - Details on parameters accepted in the built-in layers:
- Simple demo I put together for using navigation with the KUKA youBot
- This paper titled Improved Techniques for Grid Mapping with Rao-Blackwellized Particle Filters describes the mathematical foundations of gmapping.