diff --git a/nav_msgs/CMakeLists.txt b/nav_msgs/CMakeLists.txt index ee3d3c6d..b6b37763 100644 --- a/nav_msgs/CMakeLists.txt +++ b/nav_msgs/CMakeLists.txt @@ -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" diff --git a/nav_msgs/README.md b/nav_msgs/README.md index d30926b4..6856323a 100644 --- a/nav_msgs/README.md +++ b/nav_msgs/README.md @@ -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. diff --git a/nav_msgs/msg/Trajectory.msg b/nav_msgs/msg/Trajectory.msg new file mode 100644 index 00000000..cb796629 --- /dev/null +++ b/nav_msgs/msg/Trajectory.msg @@ -0,0 +1,7 @@ +# An array of trajectory points that represents a trajectory for a robot to follow. + +# Indicates the frame_id in which the planner ran and timestamp represents when the trajectory was generated. +std_msgs/Header header + +# Array of trajectory points to follow. +TrajectoryPoint[] points diff --git a/nav_msgs/msg/TrajectoryPoint.msg b/nav_msgs/msg/TrajectoryPoint.msg new file mode 100644 index 00000000..dde4b17f --- /dev/null +++ b/nav_msgs/msg/TrajectoryPoint.msg @@ -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, linear.x component is NaN if not set). +geometry_msgs/Accel acceleration + +# Force/Torque to apply at trajectory sample (optional, force.x component is NaN if not set). +geometry_msgs/Wrench effort