Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
15 commits
Select commit Hold shift + click to select a range
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
4 changes: 4 additions & 0 deletions control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ set(msg_files
msg/JointJog.msg
msg/JointTolerance.msg
msg/JointTrajectoryControllerState.msg
msg/JointWrenchTrajectory.msg
msg/JointWrenchTrajectoryPoint.msg
msg/MecanumDriveControllerState.msg
msg/MotionArgument.msg
msg/MotionPrimitive.msg
Expand All @@ -35,13 +37,15 @@ set(msg_files
msg/SteeringControllerStatus.msg
msg/SteeringControllerCommand.msg
msg/SpeedScalingFactor.msg
msg/WrenchFramed.msg
)

set(action_files
action/ExecuteMotionPrimitiveSequence.action
action/FollowJointTrajectory.action
action/GripperCommand.action
action/JointTrajectory.action
action/FollowJointWrenchTrajectory.action
action/ParallelGripperCommand.action
action/PointHead.action
action/SingleJointPosition.action
Expand Down
59 changes: 59 additions & 0 deletions control_msgs/action/FollowJointWrenchTrajectory.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# The joint trajectory to follow
control_msgs/JointWrenchTrajectory trajectory

# Tolerances for the trajectory. If the measured joint values fall
# outside the tolerances the trajectory goal is aborted. Any
# tolerances that are not specified (by being omitted or set to 0) are
# set to the defaults for the action server (often taken from the
# parameter server).

# Tolerances applied to the joints as the trajectory is executed. If
# violated, the goal aborts with error_code set to
# PATH_TOLERANCE_VIOLATED.
control_msgs/JointTolerance[] path_tolerance

# To report success, the joints must be within goal_tolerance of the
# final trajectory value. The goal must be achieved by time the
# trajectory ends plus goal_time_tolerance. (goal_time_tolerance
# allows some leeway in time, so that the trajectory goal can still
# succeed even if the joints reach the goal some time after the
# precise end time of the trajectory).
#
# If the joints are not within goal_tolerance after "trajectory finish
# time" + goal_time_tolerance, the goal aborts with error_code set to
# GOAL_TOLERANCE_VIOLATED
control_msgs/JointTolerance[] goal_tolerance
builtin_interfaces/Duration goal_time_tolerance

---
int32 error_code
int32 SUCCESSFUL = 0
int32 INVALID_GOAL = -1
int32 INVALID_JOINTS = -2
int32 OLD_HEADER_TIMESTAMP = -3
int32 PATH_TOLERANCE_VIOLATED = -4
int32 GOAL_TOLERANCE_VIOLATED = -5
int32 TRAJECTORY_ABORTED = -6

# Human readable description of the error code. Contains complementary
# information that is especially useful when execution fails, for instance:
# - INVALID_GOAL: The reason for the invalid goal (e.g., the requested
# trajectory requires a command that differ significantly from the
# robot's current state).
# - INVALID_JOINTS: The mismatch between the expected controller joints
# and those provided in the goal.
# - PATH_TOLERANCE_VIOLATED and GOAL_TOLERANCE_VIOLATED: Which joint
# violated which tolerance, and by how much.
# - TRAJECTORY_ABORTED: Indicates that the trajectory was aborted during
# execution (e.g., another trajectory was sent for execution, or a
# problem occurred).
string error_string

---
std_msgs/Header header
string[] joint_names
control_msgs/JointWrenchTrajectoryPoint desired
control_msgs/JointWrenchTrajectoryPoint actual
control_msgs/JointWrenchTrajectoryPoint error
# the currently used point from trajectory.points array
int32 index
10 changes: 10 additions & 0 deletions control_msgs/msg/JointWrenchTrajectory.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# The header is used to specify the reference time for the trajectory durations
std_msgs/Header header

# The names of the active joints in each trajectory point. These names are
# ordered and must correspond to the values in each trajectory point.
string[] joint_names

# Array of trajectory points, which describe the joint positions, velocities,
# accelerations and/or efforts, and task space wrenches at each time point.
control_msgs/JointWrenchTrajectoryPoint[] points
6 changes: 6 additions & 0 deletions control_msgs/msg/JointWrenchTrajectoryPoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# A joint-wrench trajectory point defines joint positions, joint velocities, joint accelerations, joint efforts, and a task space wrench, typically used by controllers.
# Note: The time_from_start field is included in the JointTrajectoryPoint.
trajectory_msgs/JointTrajectoryPoint point

# The task-space wrench to apply at this trajectory point.
control_msgs/WrenchFramed wrench
7 changes: 7 additions & 0 deletions control_msgs/msg/WrenchFramed.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# This message represents a wrench (force and torque) expressed in a specific reference frame.

# The reference frame in which the wrench is expressed.
string frame_id

# The wrench applied.
geometry_msgs/Wrench wrench