ROS2 Topics#
The WMX ROS2 application uses topics for real-time data streaming: encoder feedback from the robot and motion commands to the WMX engine. Topics are divided into published (output) and subscribed (input) categories.
Topic |
Message Type |
Direction |
Rate |
Node |
|---|---|---|---|---|
|
|
Published |
On change |
|
|
|
Published |
500 Hz |
|
|
|
Published |
500 Hz |
|
|
|
Published |
500 Hz |
|
|
|
Published |
100 Hz |
|
|
|
Subscribed |
On demand |
|
|
|
Subscribed |
On demand |
|
|
|
Subscribed |
On demand |
|
Custom Message Types#
Before reviewing the topics, here are the custom message type definitions
from wmx_ros2_message.
wmx_ros2_message/msg/AxisState
int32[] amp_alarm # Amplifier alarm active per axis
int32[] servo_on # Servo enabled per axis
int32[] home_done # Homing completed per axis
int32[] in_pos # At target position per axis
int32[] negative_ls # Negative limit switch active per axis
int32[] positive_ls # Positive limit switch active per axis
int32[] home_switch # Home switch active per axis
float64[] pos_cmd # Commanded position per axis (radians)
float64[] velocity_cmd # Commanded velocity per axis (rad/s)
float64[] actual_pos # Actual encoder position per axis (radians)
float64[] actual_velocity # Actual velocity per axis (rad/s)
float64[] actual_torque # Actual torque per axis (Nm)
wmx_ros2_message/msg/AxisPose
int32[] index # Axis indices to command
float64[] target # Target positions (radians)
string profile # Motion profile type (reserved)
float64[] velocity # Motion velocity per axis (rad/s)
float64[] acc # Acceleration per axis (rad/s^2)
float64[] dec # Deceleration per axis (rad/s^2)
wmx_ros2_message/msg/AxisVelocity
int32[] index # Axis indices to command
string profile # Motion profile type (reserved)
float64[] velocity # Target velocity per axis (rad/s)
float64[] acc # Acceleration per axis (rad/s^2)
float64[] dec # Deceleration per axis (rad/s^2)
Published Topics#
Engine Ready Signal#
/wmx/engine/ready#
Message Type |
|
Publisher |
|
Rate |
Published on state change (not periodic) |
Purpose |
Signals to dependent nodes ( |
data=true is published once StartCommunication succeeds.
data=false is published on shutdown.
Example:
ros2 topic echo /wmx/engine/ready
Joint State Feedback#
/joint_states#
Message Type |
|
Publisher |
|
Rate |
500 Hz (configurable via |
Configurable |
Topic name set via |
Source |
|
The primary joint state topic used by MoveIt2, RViz, and other ROS2 consumers. Publishes encoder feedback for all 6 robot joints plus 2 gripper finger joints.
Field |
Type |
Description |
|---|---|---|
|
|
Current ROS2 time (set before publishing) |
|
|
Empty (default) |
|
|
8 joint names: |
|
|
8 values: 6 joint positions ( |
|
|
8 values: 6 joint velocities ( |
|
|
Empty (not populated) |
The gripper positions (indices 6 and 7) are derived from the EtherCAT
digital I/O output bit 0 via Io::GetOutBit(0, 0). When the gripper is
closed (bit=1), they report the gripper_close_value parameter (default
0.045); when open (bit=0), the gripper_open_value parameter (default
0.00).
Example – Monitor joint states:
ros2 topic echo /joint_states
Example – Check publishing rate:
ros2 topic hz /joint_states
Expected: approximately 500 Hz.
Example – View only joint positions:
ros2 topic echo /joint_states --field position
Simulator Integration Topics#
/isaacsim/joint_command#
Message Type |
|
Publisher |
|
Rate |
500 Hz (same timer as |
Configurable |
Topic name set via |
Platform |
Orin config only (Intel config does not set this topic) |
Purpose |
Mirror joint states for NVIDIA Isaac Sim integration |
Same data content as /joint_states (8 joint names, positions, velocities).
Note
This topic is published before the header.stamp is set in the
encoderJointStep() callback. The timestamp in the Isaac Sim message
will be unset (zero). This is an implementation detail of the publish
order in the source code.
Example:
ros2 topic echo /isaacsim/joint_command
/gazebo_position_controller/commands#
Message Type |
|
Publisher |
|
Rate |
500 Hz (same timer as |
Configurable |
Topic name set via |
Platform |
Intel config only (Orin config does not set this topic) |
Purpose |
Mirror joint positions for Gazebo simulation integration |
Publishes 8 position values (6 joint positions + 2 gripper positions) as a
flat Float64MultiArray. The array is pre-sized to 8 elements.
Field |
Type |
Description |
|---|---|---|
|
|
8 values: 6 joint positions in radians ( |
Example:
ros2 topic echo /gazebo_position_controller/commands
Axis State Monitoring#
/wmx/axis/state#
Message Type |
|
Publisher |
|
Rate |
100 Hz (hardcoded |
Axis Count |
2 (hardcoded |
Source |
|
Purpose |
Detailed per-axis status from the WMX CoreMotion API |
Publishes comprehensive axis status including servo state, alarm status, limit switches, commanded vs. actual positions, velocities, and torques.
Important
The axis count is hardcoded to 2 in wmx_core_motion_node.hpp
(axisCount_=2). This means the arrays in AxisState contain 2
elements each, monitoring axes 0 and 1 only.
Field |
Type |
Description |
|---|---|---|
|
|
Amplifier alarm active per axis ( |
|
|
Servo drive enabled per axis ( |
|
|
Homing procedure completed per axis ( |
|
|
Axis has reached commanded position ( |
|
|
Negative limit switch triggered per axis ( |
|
|
Positive limit switch triggered per axis ( |
|
|
Home switch triggered per axis ( |
|
|
Commanded position per axis (radians) |
|
|
Commanded velocity per axis (rad/s) |
|
|
Actual encoder position per axis (radians) |
|
|
Actual velocity per axis (rad/s) |
|
|
Actual torque per axis (Nm) |
The callback clears all vectors before each publish cycle and rebuilds them
from the CoreMotion::GetStatus() result.
Example – Monitor axis state:
ros2 topic echo /wmx/axis/state
Example – Check for alarms:
ros2 topic echo /wmx/axis/state --field amp_alarm
Subscribed Topics (Motion Commands)#
These topics accept motion commands and are subscribed to by the
wmx_core_motion_node (source: wmx_core_motion_node.cpp). Publishing
to these topics directly controls the WMX engine and moves real motors.
Warning
Publishing to these topics will cause immediate physical motion. Ensure the robot workspace is clear and all safety precautions are in place.
/wmx/axis/velocity#
Message Type |
|
Subscriber |
|
Callback |
|
Purpose |
Command continuous velocity motion on specified axes |
For each axis in msg->index, the callback:
Sets
velocity_.axisto the axis indexSets the velocity profile to
ProfileType::TrapezoidalSets velocity, acceleration, and deceleration from the message
Calls
CoreMotion::StartVel(&velocity_)
The axis must be in velocity mode (see ROS2 Services for
/wmx/axis/set_mode with data=[1]).
Example – Rotate axis 0 at 1.0 rad/s:
ros2 topic pub --once /wmx/axis/velocity wmx_ros2_message/msg/AxisVelocity \
"{index: [0], profile: '', velocity: [1.0], acc: [10.0], dec: [10.0]}"
Example – Stop axis 0:
ros2 topic pub --once /wmx/axis/velocity wmx_ros2_message/msg/AxisVelocity \
"{index: [0], profile: '', velocity: [0.0], acc: [10.0], dec: [10.0]}"
/wmx/axis/position#
Message Type |
|
Subscriber |
|
Callback |
|
Purpose |
Command absolute position motion on specified axes |
For each axis in msg->index, the callback:
Sets
position_.axisto the axis indexSets
position_.targetto the target positionSets the profile to
ProfileType::TrapezoidalSets velocity, acceleration, and deceleration from the message
Calls
CoreMotion::StartPos(&position_)– absolute positioning
The target values are absolute positions in radians relative to the home
position.
Example – Move axis 0 to 1.5 radians:
ros2 topic pub --once /wmx/axis/position wmx_ros2_message/msg/AxisPose \
"{index: [0], target: [1.5], profile: '', velocity: [5.0], acc: [10.0], dec: [10.0]}"
/wmx/axis/position/relative#
Message Type |
|
Subscriber |
|
Callback |
|
Purpose |
Command relative position motion on specified axes |
For each axis in msg->index, the callback:
Sets
position_.axisto the axis indexSets
position_.targetto the relative displacementSets the profile to
ProfileType::TrapezoidalSets velocity, acceleration, and deceleration from the message
Calls
CoreMotion::StartMov(&position_)– relative movement
The target values are relative displacements in radians from the current
position.
Example – Move axis 0 by +0.5 radians from current position:
ros2 topic pub --once /wmx/axis/position/relative wmx_ros2_message/msg/AxisPose \
"{index: [0], target: [0.5], profile: '', velocity: [5.0], acc: [10.0], dec: [10.0]}"
Differential Drive Topics (Optional)#
The diff_drive_controller node provides topics for mobile base control.
This node is currently disabled in the build (commented out in
CMakeLists.txt).
Note
The differential drive controller is not built by default. It must be
enabled in CMakeLists.txt to use these topics.
/cmd_vel (Subscribed)#
Message Type |
|
Subscriber |
|
Configurable |
Topic name set via |
Purpose |
Receive linear/angular velocity commands for the mobile base |
The cmdCallback() stores the incoming Twist message and republishes it.
The cmdVelStep() timer (at rate Hz) then:
Checks engine state is
CommunicatingChecks for amplifier alarms and servo status on both wheel axes
Computes wheel angular velocities using differential drive kinematics:
left_omega = (2 * linear.x - angular.z * wheel_to_wheel) / (2 * wheel_radius)right_omega = (2 * linear.x + angular.z * wheel_to_wheel) / (2 * wheel_radius)
Calls
CoreMotion::StartVel()for each wheel axis
/cmd_vel_check (Published)#
Message Type |
|
Publisher |
|
Configurable |
Topic name set via |
Purpose |
Echo the received |
/velocity_controller/commands (Published)#
Message Type |
|
Publisher |
|
Configurable |
Topic name set via |
Purpose |
Publish actual wheel angular velocities from encoder feedback |
Publishes 2 values: [left_velocity, right_velocity] read from the
CoreMotion::GetStatus() result for the left and right wheel axes.
/odom_enc (Published)#
Message Type |
|
Publisher |
|
Configurable |
Topic name set via |
Purpose |
Publish encoder-based odometry (velocity only) |
Computes odometry from wheel angular velocities:
linear_vel = (right_omega * wheel_radius + left_omega * wheel_radius) / 2angular_vel = (right_omega * wheel_radius - left_omega * wheel_radius) / wheel_to_wheel
Publishes in twist.twist.linear.x and twist.twist.angular.z. The
pose fields are not populated.
See Also#
ROS2 Services – Service API for engine management and axis control
ROS2 Actions – FollowJointTrajectory action for MoveIt2 integration
wmx_ros2_message – Custom message type definitions
wmx_ros2_package – Node documentation with parameters