Skip to content
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

WIP: Add linear trajectory and traj pt messages. #1

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
8 changes: 5 additions & 3 deletions trajectory_msgs/CMakeLists.txt
@@ -1,20 +1,22 @@
cmake_minimum_required(VERSION 3.0.2)
project(trajectory_msgs)

find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs)
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs sensor_msgs)

add_message_files(
DIRECTORY msg
FILES
JointTrajectory.msg
JointTrajectoryPoint.msg
LinearTrajectory.msg
LinearTrajectoryPoint.msg
MultiDOFJointTrajectory.msg
MultiDOFJointTrajectoryPoint.msg
)

generate_messages(DEPENDENCIES std_msgs geometry_msgs)
generate_messages(DEPENDENCIES std_msgs geometry_msgs sensor_msgs)

catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs)
catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs sensor_msgs)

install(DIRECTORY rules
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
60 changes: 60 additions & 0 deletions trajectory_msgs/msg/LinearTrajectory.msg
@@ -0,0 +1,60 @@
# A linear trajectory is defined here as a list of 6D poses with associated
# timing information, and optional velocity, acceleration, forces and torques.
#
# Trajectories are defined as moving a specified Cartesian frame through a
# Cartesian coordinate system with a specified origin. It is assumed the
# location of the origin (relative to other such origins) is provided by an
# external system (fi: TF in the case of ROS).
#
# Several fields in this message are required fields. Recipients of this message
# must either ignore malformed incoming messages or return an error whenever
# possible.

# A standard ROS message header.
#
# ## header.frame_id
#
# This field provides the name of the TF frame which defines the origin of the
# coordinate system relative to which the poses in this trajectory are defined.
#
# It is an error to leave 'header.frame_id' empty.
#
# Recipients of trajectories are required to verify 'header.frame_id' and
# compare it to whichever coordinate system they intend to use for execution of
# the trajectory. In case of mismatch, they are required to transform all poses,
# velocities, accelerations and wrenches to 'header.frame_id' before proceeding
# with execution. The field 'header.stamp' should be used in this case to lookup
# the value of the transform at the correct time.
#
# Note: only a single origin is supported. Producers of trajectories are
# required to transform trajectory points relative to other origins to a
# common origin before adding them to a trajectory. Failure to do so will most
# likely result in unintended and/or unexpected motion.
#
# ## header.seq
#
# This field is not used.
#
# ## header.stamp
#
# This field is set to the time at which the trajectory was created.
#
# TODO: align semantics of 'stamp' with JointTrajectory::header.
std_msgs/Header header

# The trajectory describes the motion of this frame relative to
# 'header.frame_id'.
#
# It is an error to leave this field empty.
string child_frame_id

# List of points in this trajectory.
#
# Each point in the trajectory specifies at least a valid pose and a time at
# which that pose must be reached by 'child_frame_id'.
#
# All other fields are optional.
#
# Refer to the documentation of 'LinearTrajectoryPoint' for more information
# on the contents of its fields.
trajectory_msgs/LinearTrajectoryPoint[] points
76 changes: 76 additions & 0 deletions trajectory_msgs/msg/LinearTrajectoryPoint.msg
@@ -0,0 +1,76 @@
# Time (in seconds) at which the system state encoded in this trajectory point
# is to be attained, relative to the start of trajectory execution.
#
# Required field.
#
# It is an error to not initialise this field.
duration time_from_start

# Cartesian pose to achieve at time 'time_from_start' (relative to the start
# of trajectory execution).
#
# Required field.
#
# It is an error to not initialise this field.
geometry_msgs/Pose pose

# Target state at 'pose' (link-local velocities).
#
# TODO: how to make this field optional?
geometry_msgs/Twist velocity

# Target state at 'pose' (link-local accelerations).
#
# TODO: how to make this field optional?
geometry_msgs/Accel acceleration

# Target state at 'pose' (link-local forces and torques).
#
# TODO: how to make this field optional?
geometry_msgs/Wrench wrench

# Preferred joint space configuration to achieve 'pose'.
#
# Optional field.
#
# This field is encoded as a 'sensor_msgs/JointState' to allow for the greatest
# flexibility when describing joint configurations (compared to bitmasks or
# lists of booleans/integers).
#
# Only the 'name' and 'position' fields of the JointState message are used.
# Values in other fields are ignored.
#
# Joints present in the system, but for which no values are provided will be
# considered unrestricted wrt possible IK solutions (ie: so called 'free'
# joints).
#
# Leaving this field empty in case of kinematic systems for which multiple IK
# solutions exist for a given pose, in general or because of their by-design
# underconstraint nature (ie: in case of (hyper-)redundancy), could lead to
# motion discontinuities (ie: mid-motion configuration changes) as IK solvers
# may not provide the closest or preferred solutions automatically for those
# types of systems.
#
# Example of a 6D kinematic configuration with all joints given values:
#
# configuration.name = ['joint_1', 'joint_2', ..., 'joint_6']
# configuration.position = [0.1092, 0.4012, ..., 1.6323]
#
# Drivers moving robots to this trajectory point are required to use an IK
# solution either identical to or as close as possible to this joint
# configuration.
#
# Encoding a "configuration bitmask" (ie: shoulder, elbow, wrist) typically
# used in industrial robotics into a 'configuration' field may be done as
# follows:
#
# configuration.name = ['joint_2', 'joint_3', 'joint_4']
# configuration.position = [0.0, 0.0, 3.1415]
#
# Note: if only 'joint_4' would have been specified, the shoulder and elbow
# joints would not have been constrained, leading to potentially different
# solutions being used.
#
# Also note: as 'configuration' encodes joint angles instead of binary states,
# turn numbers and configuration flags can be expressed as a single joint angle.
sensor_msgs/JointState configuration
2 changes: 2 additions & 0 deletions trajectory_msgs/package.xml
Expand Up @@ -16,10 +16,12 @@

<build_depend>message_generation</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>

<run_depend>message_runtime</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>rosbag_migration_rule</run_depend>

Expand Down