ROS Navigation
Overview
- ROS Nav2 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 thebase_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 themap
frame. Thus the transform frommap -> base_link
is always the map estimate.
- The transform from
- The map frame can sometimes be the child of a
world
orearth
frame
Conceptual Components
- Base Controller: Subscribes to a
geometry_msgs/Twist
(by default on thecmd_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
odom
tf
transform. - Odometry and the Base controller are often a single node but need not be
- This message is used to publish the
- Sensors: Including laser scanners (publishing
sensor_msgs/LaserScan
) or depth cameras publishingsensor_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
- Global cost map - this is the overall environment, used for global planners such as
- 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
Other Packages (ROS 1)
- carrot_planner A global planner that gets robots as close to obstacles as possible
- sbpl Search based planning library: a global planner based on "motion primitives"
- fake_localization Uses odometry information to provide the same localization messages as
amcl
Used for simulation and debugging. - voxel_grid 3 Dimensional pixel grid, useful for representing 3 dimensional cost maps.
- google_cartographer_ros ROS support for google's SLAM implementations
- This is quite complicated to tune and setup.
- 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.