From d24e8ad299db245647e5d6d3da12b5d53c969429 Mon Sep 17 00:00:00 2001 From: Ahsan Yusob Date: Sat, 3 May 2025 23:09:22 +0200 Subject: [PATCH] Added BaseTrajectory message definition in trajectory_msgs Signed-off-by: Ahsan Yusob --- trajectory_msgs/CMakeLists.txt | 2 ++ trajectory_msgs/README.md | 2 ++ trajectory_msgs/msg/BaseTrajectory.msg | 11 +++++++++ trajectory_msgs/msg/BaseTrajectoryPoint.msg | 27 +++++++++++++++++++++ 4 files changed, 42 insertions(+) create mode 100644 trajectory_msgs/msg/BaseTrajectory.msg create mode 100644 trajectory_msgs/msg/BaseTrajectoryPoint.msg diff --git a/trajectory_msgs/CMakeLists.txt b/trajectory_msgs/CMakeLists.txt index f3edac2f..89e95ff6 100644 --- a/trajectory_msgs/CMakeLists.txt +++ b/trajectory_msgs/CMakeLists.txt @@ -18,6 +18,8 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) set(msg_files + "msg/BaseTrajectory.msg" + "msg/BaseTrajectoryPoint.msg" "msg/JointTrajectory.msg" "msg/JointTrajectoryPoint.msg" "msg/MultiDOFJointTrajectory.msg" diff --git a/trajectory_msgs/README.md b/trajectory_msgs/README.md index 71bf260b..5c2d58c1 100644 --- a/trajectory_msgs/README.md +++ b/trajectory_msgs/README.md @@ -5,6 +5,8 @@ This package provides several messages for defining robotic joint trajectories. For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). ## Messages (.msg) +* [BaseTrajectory](msg/BaseTrajectory.msg): A time-parameterized sequence of poses, velocities, and accelerations for a mobile robot base to follow, typically relative to a fixed global frame. +* [BaseTrajectoryPoint](msg/BaseTrajectoryPoint.msg): A single target pose, velocity, and acceleration for the robot base at a specific time from the start of the trajectory. * [JointTrajectory](msg/JointTrajectory.msg): A coordinated sequence of joint configurations to be reached at prescribed time points. * [JointTrajectoryPoint](msg/JointTrajectoryPoint.msg): A single configuration for multiple joints in a JointTrajectory. * [MultiDOFJointTrajectory](msg/MultiDOFJointTrajectory.msg): A representation of a multi-dof joint trajectory (each point is a transformation). diff --git a/trajectory_msgs/msg/BaseTrajectory.msg b/trajectory_msgs/msg/BaseTrajectory.msg new file mode 100644 index 00000000..51cebff5 --- /dev/null +++ b/trajectory_msgs/msg/BaseTrajectory.msg @@ -0,0 +1,11 @@ +# The header is used to specify the coordinate frame and the reference time for +# the trajectory durations +std_msgs/Header header + +# The names of the active waypoint in each trajectory point. These names are +# ordered and must correspond to the values in each trajectory point. +string[] waypoint_name + +# Array of trajectory points, which describe the poses, velocities, +# and/or accelerations of the base at each time point. +BaseTrajectoryPoint[] points diff --git a/trajectory_msgs/msg/BaseTrajectoryPoint.msg b/trajectory_msgs/msg/BaseTrajectoryPoint.msg new file mode 100644 index 00000000..e9636af7 --- /dev/null +++ b/trajectory_msgs/msg/BaseTrajectoryPoint.msg @@ -0,0 +1,27 @@ +# Each trajectory point specifies the target pose[, velocity[, acceleration]] +# for the robot base at a specific time from the trajectory start. +# +# This message is analogous to JointTrajectoryPoint, but applies to a mobile +# base or any frame tied to base_link. +# +# This message is particularly useful as an input to a trajectory or path-following +# controller, where each point specifies the desired base pose, velocity, and +# acceleration at a given time along the trajectory. +# The pose, velocity, and acceleration are all expressed in the frame specified +# by the parent trajectory's header.frame_id (e.g., "map", "odom", or similar). + +# Target pose of the robot base (e.g., base_link) in the planning frame. +geometry_msgs/Pose pose + +# Desired velocity of the base at this trajectory point. +# This includes both linear (m/s) and angular (rad/s) components. +# Twist is expressed in the same frame as pose. +geometry_msgs/Twist velocity + +# Desired acceleration of the base at this trajectory point. +# This includes both linear (m/s^2) and angular (rad/s^2) components. +# Twist is expressed in the same frame as pose. +geometry_msgs/Twist acceleration + +# Desired time from the start of the trajectory to arrive at this point. +builtin_interfaces/Duration time_from_start