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. |
Using rviz with the Navigation Stack
Description: This tutorial provides a guide to using rviz with the navigation stack to initialize the localization system, send goals to the robot, and view the many visualizations that the navigation stack publishes over ROS.Keywords: navigation rviz debugging
Tutorial Level: BEGINNER
Contents
Overview
rviz is a powerful visualization tool that can be used for many different purposes. This tutorial assumes at least some familiarity with rviz on which documentation can be found here.
Setting Up rviz for the Navigation Stack
The following video shows how to setup rviz to work with the navigation stack. This includes setting the pose of the robot for a localization system like amcl, displaying all the visualization information that the navigation stack provides, and sending goals to the navigation stack with rviz. Discussions of each visualization topic the navstack publishes can be found below.
2D Nav Goal
Topic: move_base_simple/goal
Description: Allows the user to send a goal to the navigation by setting a desired pose for the robot to achieve.
2D Pose Estimate
Topic: initialpose
Description: Allows the user to initialize the localization system used by the navigation stack by setting the pose of the robot in the world.
Static Map
Topic: map
Type: nav_msgs/GetMap
Type: nav_msgs/OccupancyGrid
Description: Displays the static map that is being served by the map_server if one exists.
Particle Cloud
Topic: particlecloud
Type: geometry_msgs/PoseArray
Description: Displays the particle cloud used by the robot's localization system. The spread of the cloud represents the localization system's uncertainty about the robot's pose. A cloud that is very spread out reflects high uncertainty, while a condensed cloud represents low uncertainty.
Robot Footprint
Topic: local_costmap/robot_footprint
- Description: Displays the footprint of the robot
Obstacles
Topic: local_costmap/obstacles
Type: nav_msgs/GridCells
Desctiption: Displays the obstacles that the navigation stack sees in its costmap. For the robot to avoid collision, the robot footprint should never intersect with a cell that contains an obstacle.
Inflated Obstacles
Topic: local_costmap/inflated_obstacles
Type: nav_msgs/GridCells
Description: Displays obstacles in the navigation stack's costmap inflated by the inscribed radius of the robot. For the robot to avoid collision, the center point of the robot should never overlap with a cell that contains an inflated obstacle.
Unknown Space
Topic: local_costmap/unknown_space
Type: nav_msgs/GridCells
Description: Displays any unknown space contained in the navigation stack's costmap_2d.
Global Plan
Topic: TrajectoryPlannerROS/global_plan
Type: nav_msgs/Path
Description: Displays the portion of the global plan that the local planner is currently pursuing.
Local Plan
Topic: TrajectoryPlannerROS/local_plan
Type: nav_msgs/Path
Description: Displays the trajectory associated with the velocity commands currently being commanded to the base by the local planner.
Planner Plan
Topic: NavfnROS/plan
Type: nav_msgs/Path
Description: Displays the full plan for the robot computed by the global planner.
Current Goal
Topic: current_goal
- Description: Displays the goal pose that the navigation stack is attempting to achieve.