Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions nav_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ set(msg_files
"msg/OccupancyGrid.msg"
"msg/Odometry.msg"
"msg/Path.msg"
"msg/Trajectory.msg"
"msg/TrajectoryPoint.msg"
)
set(srv_files
"srv/GetMap.srv"
Expand Down
2 changes: 2 additions & 0 deletions nav_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros
* [OccupancyGrid](msg/OccupancyGrid.msg): Represents a 2-D grid map, in which each cell represents the probability of occupancy.
* [Odometry](msg/Odometry.msg): This represents an estimate of a position and velocity in free space.
* [Path](msg/Path.msg): An array of poses that represents a Path for a robot to follow.
* [Trajectory](msg/Trajectory.msg): A representation of a trajectory as a series of time-stamped trajectory points.
* [TrajectoryPoint](msg/TrajectoryPoint.msg): A single point in a trajectory.

## Services (.srv)
* [GetMap](srv/GetMap.srv): Get the map as a nav_msgs/OccupancyGrid.
Expand Down
7 changes: 7 additions & 0 deletions nav_msgs/msg/Trajectory.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# An array of trajectory points that represents a trajectory for a robot to follow.

# Indicates the frame_id and timestamp of the trajectory.
std_msgs/Header header

# Array of trajectory points to follow.
TrajectoryPoint[] points
16 changes: 16 additions & 0 deletions nav_msgs/msg/TrajectoryPoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# Trajectory point state

# Absolute time and frame of reference of the point along a trajectory
std_msgs/Header header

# Pose of the trajectory sample.
geometry_msgs/Pose pose

# Velocity of the trajectory sample.
geometry_msgs/Twist velocity

# Acceleration of the trajectory (optional, NaN if not set).
geometry_msgs/Accel acceleration

# Force/Torque to apply at trajectory sample (optional, NaN if not set).
geometry_msgs/Wrench effort