Skip to content

Commit d81f602

Browse files
Adding the Trajectory and trajectoryPoint messages (#296)
Signed-off-by: SteveMacenski <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Tully Foote <[email protected]>
1 parent c9002a4 commit d81f602

File tree

4 files changed

+27
-0
lines changed

4 files changed

+27
-0
lines changed

nav_msgs/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@ set(msg_files
2424
"msg/OccupancyGrid.msg"
2525
"msg/Odometry.msg"
2626
"msg/Path.msg"
27+
"msg/Trajectory.msg"
28+
"msg/TrajectoryPoint.msg"
2729
)
2830
set(srv_files
2931
"srv/GetMap.srv"

nav_msgs/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros
1212
* [OccupancyGrid](msg/OccupancyGrid.msg): Represents a 2-D grid map, in which each cell represents the probability of occupancy.
1313
* [Odometry](msg/Odometry.msg): This represents an estimate of a position and velocity in free space.
1414
* [Path](msg/Path.msg): An array of poses that represents a Path for a robot to follow.
15+
* [Trajectory](msg/Trajectory.msg): A representation of a trajectory as a series of time-stamped trajectory points.
16+
* [TrajectoryPoint](msg/TrajectoryPoint.msg): A single point in a trajectory.
1517

1618
## Services (.srv)
1719
* [GetMap](srv/GetMap.srv): Get the map as a nav_msgs/OccupancyGrid.

nav_msgs/msg/Trajectory.msg

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
# An array of trajectory points that represents a trajectory for a robot to follow.
2+
3+
# Indicates the frame_id in which the planner ran and timestamp represents when the trajectory was generated.
4+
std_msgs/Header header
5+
6+
# Array of trajectory points to follow.
7+
TrajectoryPoint[] points

nav_msgs/msg/TrajectoryPoint.msg

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
# Trajectory point state
2+
3+
# Absolute time and frame of reference of the point along a trajectory
4+
std_msgs/Header header
5+
6+
# Pose of the trajectory sample.
7+
geometry_msgs/Pose pose
8+
9+
# Velocity of the trajectory sample.
10+
geometry_msgs/Twist velocity
11+
12+
# Acceleration of the trajectory (optional, linear.x component is NaN if not set).
13+
geometry_msgs/Accel acceleration
14+
15+
# Force/Torque to apply at trajectory sample (optional, force.x component is NaN if not set).
16+
geometry_msgs/Wrench effort

0 commit comments

Comments
 (0)