Testing with Real Robot#
Prerequisites#
The WMX ROS2 workspace is built and sourced
LMX(WMX Runtime) is installed at
/opt/lmx/EtherCAT cable is connected between compute platform and first servo drive
Robot and all servo drives are powered on
You have
sudoprivileges
EtherCAT Wiring#
┌──────────────┐ Ethernet ┌──────────┐ ┌──────────┐ ┌──────────┐
│ Compute PC │────(EtherCAT)──►│ Servo J1 │───►│ Servo J2 │── ... ──│ Servo J6 │
│ (dedicated │ └──────────┘ └──────────┘ └──────────┘
│ NIC port) │
└──────────────┘
Use a dedicated Ethernet port for EtherCAT
Servo drives are daisy-chained (each drive has IN and OUT ports)
The I/O module for gripper control is part of the same chain
Configuration#
Platform |
Config File |
Launch File |
|---|---|---|
Intel x86_64 |
|
|
NVIDIA Jetson Orin |
|
|
Important
Update the wmx_param_file_path in the config YAML to match your actual
home directory and workspace path.
Launch Commands#
sudo --preserve-env=PATH \
--preserve-env=AMENT_PREFIX_PATH \
--preserve-env=COLCON_PREFIX_PATH \
--preserve-env=PYTHONPATH \
--preserve-env=LD_LIBRARY_PATH \
--preserve-env=ROS_DISTRO \
--preserve-env=ROS_VERSION \
--preserve-env=ROS_PYTHON_VERSION \
--preserve-env=ROS_DOMAIN_ID \
--preserve-env=RMW_IMPLEMENTATION \
bash -c "source /opt/ros/${ROS_DISTRO}/setup.bash && \
source ~/wmx_ros2_ws/install/setup.bash && \
ros2 launch wmx_ros2_package wmx_ros2_cr3a_manipulator.launch.py \
use_sim_time:=false"
Startup Sequence#
When launched, three nodes initialize in parallel:
Device creation – Each node creates a WMX device handle
EtherCAT scan – Network scan discovers all servo drives
Communication start – Real-time EtherCAT communication begins
Parameter loading – Gear ratios and axis polarities loaded from XML
Servo enable – All 6 joint servos cleared and enabled
Ready – All nodes report ready
Verifying the Connection#
ros2 node list # Expect: 3 nodes
ros2 topic hz /joint_states # Expect: ~500 Hz
ros2 topic echo /joint_states --field position # Live joint positions
ros2 service call /wmx/engine/get_status std_srvs/srv/Trigger # Expect: "Communicating"
ros2 action list # Expect: follow_joint_trajectory
Gripper Control#
# Close gripper
ros2 service call /wmx/set_gripper std_srvs/srv/SetBool "{data: true}"
# Open gripper
ros2 service call /wmx/set_gripper std_srvs/srv/SetBool "{data: false}"
Shutdown#
Press Ctrl+C in the launch terminal. The nodes will automatically disable
servos, stop EtherCAT communication, and close the WMX device.