ROS2 Actions#
The WMX ROS2 application exposes one action server for trajectory execution,
compatible with MoveIt2 and any FollowJointTrajectory action client. No
custom .action files are defined – the system uses the standard
control_msgs action type.
Action Name |
Type |
Server Node |
Status |
|---|---|---|---|
|
|
|
Active |
FollowJointTrajectory#
Action Name |
|
Action Type |
|
Server Node |
|
Configurable |
Name set via |
Source File |
|
This action server receives a joint-space trajectory (a sequence of waypoints
with timestamps) and executes it on the physical robot using the WMX
AdvancedMotion::StartCSplinePos() cubic spline interpolation engine.
Goal#
The goal uses the standard trajectory_msgs/msg/JointTrajectory message:
Field |
Type |
Description |
|---|---|---|
|
|
Joint names ( |
|
|
Ordered list of waypoints (maximum 1000 points) |
|
|
Target joint positions in radians for each waypoint |
|
|
Timestamp relative to trajectory start |
Note
Only the positions and time_from_start fields of each trajectory
point are used. The velocities, accelerations, and effort
fields are logged for diagnostics but not passed to the WMX engine –
the cubic spline interpolation is computed internally by WMX.
Result#
Field |
Type |
Description |
|---|---|---|
|
|
|
|
|
Not set by the server (default empty) |
Feedback#
No intermediate feedback is published during execution. The action server
blocks on CoreMotion::Wait() until the spline motion completes or an error
occurs.
Execution Details#
The server processes the trajectory as follows:
Goal acceptance – All incoming goals are accepted unconditionally (
ACCEPT_AND_EXECUTE). No goal validation beyond point count is performed.Thread dispatch – The
execute()callback runs in a detached thread spawned fromhandle_accepted(), allowing the action server to remain responsive.Validation – Rejects goals with more than 1000 waypoints (aborts immediately with a warning). If the adjusted point count is 0, the server succeeds immediately without commanding motion.
Timing adjustment – The first point’s
time_from_startis forced to zero. If the last point has a time interval less than 1 ms from the previous point, it is dropped to prevent interpolation errors.Spline construction – For each trajectory point, positions are packed into a
CSplinePosDatastructure and timestamps are converted to milliseconds. ThedimensionCountandaxis[]array are set to thejoint_numberparameter (typically 6).Execution –
AdvancedMotion::StartCSplinePos(0, ...)begins the interpolated motion on buffer index 0 across all joints simultaneously.Wait – The server blocks on
CoreMotion::Wait()for all axes in the selection.Result – On success,
error_code = 0and the goal succeeds. On failure, the WMX error code is returned and the goal is aborted.
Note
Cancel requests are accepted by the handle_cancel() callback, but the
blocking Wait() call does not currently check goal_handle->is_canceling().
A TODO in the source code notes this limitation.
Example Usage#
Send a simple two-point trajectory via the command line:
ros2 action send_goal \
/movensys_manipulator_arm_controller/follow_joint_trajectory \
control_msgs/action/FollowJointTrajectory \
"{trajectory: {
joint_names: ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6'],
points: [
{positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
time_from_start: {sec: 0, nanosec: 0}},
{positions: [0.5, -0.3, 0.2, 0.0, 0.1, 0.0],
time_from_start: {sec: 3, nanosec: 0}}
]
}}"
Check that the action server is available:
ros2 action list
Expected:
/movensys_manipulator_arm_controller/follow_joint_trajectory
Inspect the action interface:
ros2 action info /movensys_manipulator_arm_controller/follow_joint_trajectory
Warning
This action moves real motors. Ensure the robot workspace is clear and all safety precautions are in place before sending trajectory goals.
MoveIt2 Integration#
MoveIt2 connects to this action server as a trajectory execution controller. The typical workflow is:
MoveIt2 reads the current robot state from
/joint_statesThe planner computes a collision-free trajectory
MoveIt2 sends the trajectory as a
FollowJointTrajectorygoalThe
follow_joint_trajectory_serverexecutes it via WMX cubic splineThe
manipulator_statenode publishes real-time encoder feedback back to/joint_statesat 500 Hz
The action server name must match the controller configuration in MoveIt2.
The default name /movensys_manipulator_arm_controller/follow_joint_trajectory
is set via the joint_trajectory_action parameter in the config YAML.
See Also#
ROS2 Topics –
/joint_statestopic detailsROS2 Services –
/wmx/set_gripperservice on the same nodeMoveIt2 Motion Planning – MoveIt2 setup