UP | HOME

ROS Navigation

Overview

  • The ROS navigation stack 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. All other frames on the robot are relative to this frame
  • 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

  1. 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
  2. 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
  3. 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
  4. 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
  5. 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.
  6. 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

There are many packages available in the navigation stack

  1. amcl Adaptive Monte-Carlo Localization. A particle filter based approach to finding the robot location given a previously created map.
  2. map_server - Provides maps to the rest of the navigation stack. Also provides a map_saver node to save a map that you create.
  3. costmap_2d - An occupancy grid implementation. Multiple layers contain information about various types of obstacles.
    • "static" obstacles (e.g., a pre-existing map,
    • "inflation layer" (e.g., increasing cost near obstacles to add conservativeness)
    • "obstacle map layer" (e.g., for obstacles recently viewed by sensors).
    • Ultimately, these layers are combined into a grid with three states: occupied, free, or unknown.
    • costmap2d has additional information.
      • The costmap2d/hydro presents similar information in a slightly different way
  4. global_planner - Contains basic global planning algorithms such as A*. Publishes a nav_msgs/Path message.
  5. dwa_local_planner 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.
  6. move_base - Coordinates the global and local planners and the cost maps and publishes the geometry_msgs/Twist commands to drive the robot to a goal.
    • This is the main node of the nav-stack
    • Any robot that implements the sensors, odometry and base controller needed by move_base can be used with the ROS navigation stack
  7. nav_core Defines the software interface for the planners and enables people to write custom planners that can be used with the rest of the nav stack.
  8. slam_toolbox The most up-to-date 2D SLAM method for ROS.
    • This is going to be the main 2D SLAM package in ROS 2
  1. robot_localization
    • Estimate robot state by combining information using sensor fusion algorithms (for example, wheel odemetry and an inertial measurement unit).
    • This is 3 dimensional

Other Packages

  • 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.

Recover Nodes

There are several nodes that can implement recovery behaviors when planning fails:

  • clear_costmap_recovery Clears costmaps near the robot, eliminating any recently seen obstacles
  • move_slow_and_clear Makes robot move very slowly after clearing a costmap, as it tries to plan again
  • rotate_recovery Causes the robot to spin in place to try to get better laser scanner data, for example.

Older/ packages

  • gmapping Basic map generation and localization (SLAM): running this algorithm is how the map is produced, after which you save it using the map_server. This is the most popular 2D SLAM method in ROS and the original so you will see it recommended everywhere. But it is actually no longer maintained.
  • hector_slam SLAM method specifically designed to solve loop-closure issues present in other SLAM methods such as gmapping.
  • eband_local_planner Elastic band optimization for local planning
  • rgbdslam Old SLAM package used with RGB-D cameras
  • robot_pose_ekf Sensor fusion for a robot. Replaced by robot_localization

Example

Below is an example of how to use the ROS navigation stack with slam_toolbox #+BEGIN_SRC bash

roslaunch turtlebot3_gazebo turtlebot3_house.launch

roslaunch turtlebot3_bringup turtlebot3_remote.launch

roslaunch slam_toolbox online_async.launch

roslaunch turtlebot3_navigation move_base.launch

rosrun map_server mapsaver -f /tmp/mymap

rosrun map_server mapserver /tmp/mymap.yaml

roslaunch slam_toolbox localization.launch

roslaunch turtlebot3_navigation amcl.launch

roslaunch turtlebot3_navigation navigation.launch

Author: Matthew Elwin