Skip to content

WIP: Added BaseTrajectory messages definition in trajectory_msgs for mobile base trajectory following #281

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
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 trajectory_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
2 changes: 2 additions & 0 deletions trajectory_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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).
Expand Down
11 changes: 11 additions & 0 deletions trajectory_msgs/msg/BaseTrajectory.msg
Original file line number Diff line number Diff line change
@@ -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
27 changes: 27 additions & 0 deletions trajectory_msgs/msg/BaseTrajectoryPoint.msg
Original file line number Diff line number Diff line change
@@ -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