ROS navigation2 enables mobile robots to navigate in 2D
Provides the ability to estimate the location of the robot based on feedback from multiple sensors
Provides global and local planning capabilities
Highly configurable. To see many of the configuration options on running examples use rqt_reconfigure
A large amount of time can be spent tuning various parameters for your particular robot
Just because a robot vendor provides nav-stack support does not necessarily mean that they have tuned the parameters optimally
Frames of Reference
REP 105 defines standard ROS frames for robots, and the navigation stack adheres to this standard
Your robot should have a frame called base_link, which is the root of the robot and is at its "chassis" center.
All other frames on the robot are relative to this frame
The base_footprint link is a "non-physical" link (so no visual/collision/inertia) that is aligned with the base_link but rests
directly on the ground
The robot's location in the world, based on its wheel odometry, is expressed in the odom frame
The robot's location in the world, based on range sensors such as lidar is expressed in the map frame
The parent-child relationship between these frames (from parent to child) is map -> odom -> base_link
The transform from odom -> base_link is typically subtracted from the estimate of the robot in the map frame. Thus
the transform from map -> base_link is always the map estimate.
The map frame can sometimes be the child of a world or earth frame
Conceptual Components
Base Controller: Subscribes to a geometry_msgs/Twist (by default on the cmd_vel topic) and makes the robot move.
This is a robot-specific node that interfaces with the hardware
Odometry: nav_msgs/Odometry is a published estimate of the position and velocity of the robot, based on the wheel odometry.
This message is used to publish the odomtf transform.
Odometry and the Base controller are often a single node but need not be
Sensors: Including laser scanners (publishing sensor_msgs/LaserScan) or depth cameras publishing sensor_msgs/PointCloud2.
Help to avoid obstacles
Also used by Simultaneous localization and mapping and other localization nodes
Cost Maps: Occupancy grids representing where obstacles are located in the environment, as a grid of cells
Global cost map - this is the overall environment, used for global planners such as A*
Local cost map - the map in the immediate area, primarily used for obstacle avoidance.
Most grid locations in a cost map have 3 states: free, occupied, or uncertain
Cost Maps can have multiple layers of information and are highly customizable
For example, maps can have an inflation layer that expands obstacles to create a safe boundary around them that the
robot will not enter
Path planners: find collision free paths
Global Planner - moves robot to ultimate goal, runs at low frequency against a mostly-static global map
Local Planner - modifies the global plan to avoid collisions against a dynamic local map.
Recovery Behaviors - When a planner fails to find a path, ad-hoc behaviors can be executed to try to improve the sensor information or location of the robot
in order to retry planning
Navigation Packages
slam_toolbox the most up-to-date 2D SLAM method for ROS.
AMCL A particle filter based approach to finding the robot location given a previously
created map. Generally SLAM Toolbox in localization mode is preferred
Map Server - Provides maps to the rest of the navigation stack and allows saving them.
Costmap 2D An occupancy grid implementation. Multiple layers contain information about various types of obstacles and are rated with a cost to travel through the cell ranging from 0 (free) to 254 (fully blocked).
"static" layer (e.g., static obstacles from a pre-existing map produced by SLAM),
"inflation" layer (e.g., increasing cost near obstacles to keep the robot even farther away and make navigation more conservative)
"obstacle" layer (e.g., for obstacles recently viewed by 2-Dimensional LaserScan and PointCloud2 data).
"voxel" layer (like the obstacle layer but capable of incorporating data from 3D sensors)
"range" layer (used for data from sonar or infrared sensors)
Custom layers are also possible because each layer is implemented as a plugin.
There are typically two costmaps setup: a "global costmap" setup for long-term planning and a "local costmap" for collision avoidance and short-term planning
nav2_planner (global_planner in ROS 1) - Contains basic global planning algorithms such as A*. Publishes a nav_msgs/Path message.
nav2_controller - the local planner (called local planner in ROS 1). Handles navigation around obstacles that pop up from sensor data
DWB (dwa_local_planner in ROS 1) Dynamic window approach local planner (the default local planner). Integrates kinematics of robot forward in time given
the possible controls. Then it predicts a trajectory and rates it based on if there is a collision and other criteria such as distance from the global plan.
rtabmap_ros RGB-D SLAM with provision for detecting loop closure.
laser_scan_matcher Provides odometry based on laser scan. It estimates the transform between two laser scans.
Many uses including: standalone odometry or input for robot_localization.
robot_navigation2 The "spiritual successor" to the ROS navigation package
move_base_flex Replacement for move_base with enhanced capabilities.