nav_msgs¶
Contents:
Summary¶
-
nav_msgs
¶ Version: 1.12.3
Description: nav_msgs defines the common messages used to interact with the navigation stack.
Maintainers: - Tully Foote <tfoote AT osrfoundation DOT org>
Licenses: - BSD
Urls: - website<http://wiki.ros.org/nav_msgs>
Authors: - Tully Foote
BuildDepends: BuildtoolDepends: BuildExportDepends: ExecDepends: Exports: - <architecture_independent/>
Types¶
Message types¶
-
nav_msgs/MapMetaData
¶ Field: - map_load_time (time) –
- resolution (float32) –
- width (uint32) –
- height (uint32) –
- origin (geometry_msgs/Pose) –
This hold basic information about the characterists of the OccupancyGrid
The time at which the map was loaded
# This hold basic information about the characterists of the OccupancyGrid # The time at which the map was loaded time map_load_time # The map resolution [m/cell] float32 resolution # Map width [cells] uint32 width # Map height [cells] uint32 height # The origin of the map [m, m, rad]. This is the real-world pose of the # cell (0,0) in the map. geometry_msgs/Pose origin
-
nav_msgs/Odometry
¶ Field: - header (std_msgs/Header) –
- child_frame_id (string) –
- pose (geometry_msgs/PoseWithCovariance) –
- twist (geometry_msgs/TwistWithCovariance) –
This represents an estimate of a position and velocity in free space. The pose in this message should be specified in the coordinate frame given by header.frame_id. The twist in this message should be specified in the coordinate frame given by the child_frame_id
# This represents an estimate of a position and velocity in free space. # The pose in this message should be specified in the coordinate frame given by header.frame_id. # The twist in this message should be specified in the coordinate frame given by the child_frame_id Header header string child_frame_id geometry_msgs/PoseWithCovariance pose geometry_msgs/TwistWithCovariance twist
-
nav_msgs/GridCells
¶ Field: - header (std_msgs/Header) –
- cell_width (float32) –
- cell_height (float32) –
- cells[] (geometry_msgs/Point) –
an array of cells in a 2D grid
#an array of cells in a 2D grid Header header float32 cell_width float32 cell_height geometry_msgs/Point[] cells
-
nav_msgs/Path
¶ Field: - header (std_msgs/Header) –
- poses[] (geometry_msgs/PoseStamped) –
An array of poses that represents a Path for a robot to follow
#An array of poses that represents a Path for a robot to follow Header header geometry_msgs/PoseStamped[] poses
-
nav_msgs/OccupancyGrid
¶ Field: - header (std_msgs/Header) –
- info (nav_msgs/MapMetaData) –
- data[] (int8) –
This represents a 2-D grid map, in which each cell represents the probability of occupancy.
# This represents a 2-D grid map, in which each cell represents the probability of # occupancy. Header header #MetaData for the map MapMetaData info # The map data, in row-major order, starting with (0,0). Occupancy # probabilities are in the range [0,100]. Unknown is -1. int8[] data
Service types¶
-
nav_msgs/SetMap
¶ Field (Request): - map (nav_msgs/OccupancyGrid) –
- initial_pose (geometry_msgs/PoseWithCovarianceStamped) –
Field (Response): - success (bool) –
Set a new map together with an initial pose
# Set a new map together with an initial pose nav_msgs/OccupancyGrid map geometry_msgs/PoseWithCovarianceStamped initial_pose --- bool success
-
nav_msgs/GetMap
¶ Field (Response): - map (nav_msgs/OccupancyGrid) –
# Get the map as a nav_msgs/OccupancyGrid --- nav_msgs/OccupancyGrid map
-
nav_msgs/GetPlan
¶ Field (Request): - start (geometry_msgs/PoseStamped) –
- goal (geometry_msgs/PoseStamped) –
- tolerance (float32) –
Field (Response): - plan (nav_msgs/Path) –
Get a plan from the current position to the goal Pose
The start pose for the plan
# Get a plan from the current position to the goal Pose # The start pose for the plan geometry_msgs/PoseStamped start # The final pose of the goal position geometry_msgs/PoseStamped goal # If the goal is obstructed, how many meters the planner can # relax the constraint in x and y before failing. float32 tolerance --- nav_msgs/Path plan
Action types¶
-
nav_msgs/GetMap
¶ Field (Result): - map (nav_msgs/OccupancyGrid) –
# Get the map as a nav_msgs/OccupancyGrid --- nav_msgs/OccupancyGrid map --- # no feedback