-
Notifications
You must be signed in to change notification settings - Fork 71
Description
Hi =D
I am trying to control three Everest XCR drives using ROS2 EtherCAT driver. I followed the instructions from this guide. However, I can only enable and move one drive (Drive 3), while the others do not reach the "operation enabled" state.
Since my 3 drives have different product IDs, I created separate YAML configuration files for each of them. I also attempted to switch the RPDO and TPDO orders without success. Below are the details of the configuration for each drive.
The drive's reference manual manual
EtherCAT & CANopen registers link
Configuration for Drive 1 (EVE XCR):
# Configuration file for Ingenia EVE-XCR-E drive
vendor_id: 0x0000029c
product_id: 0x02c30001
auto_fault_reset: true
tpdo:
- index: 0x1a00
channels:
- {index: 0x6041, sub_index: 0, type: uint16, state_interface: status_word}
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position, factor: 0.0000001198422491}
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity, factor: 0.00006283185307}
- {index: 0x6061, sub_index: 0, type: int8, state_interface: mode_of_operation}
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort}
rpdo:
- index: 0x1600
channels:
- {index: 0x6040, sub_index: 0, type: uint16, command_interface: control_word}
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position}
- {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity}
- {index: 0x6060, sub_index: 0, type: int8, command_interface: mode_of_operation, default: 8}
- {index: 0x6071, sub_index: 0, type: int16, command_interface: effort}
Configuration for Drive 2 (EVE XCR):
vendor_id: 0x0000029c
product_id: 0x02c31001
auto_fault_reset: true
rpdo:
- index: 0x1600
channels:
- {index: 0x6040, sub_index: 0, type: uint16, command_interface: control_word}
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position}
- {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity}
- {index: 0x6060, sub_index: 0, type: int8, command_interface: mode_of_operation, default: 8}
- {index: 0x6071, sub_index: 0, type: int16, command_interface: effort}
tpdo:
- index: 0x1a00
channels:
- {index: 0x6041, sub_index: 0, type: uint16, state_interface: status_word}
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position, factor: 0.0000002396844981}
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity, factor: 0.0001256637061}
- {index: 0x6061, sub_index: 0, type: int8, state_interface: mode_of_operation}
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort}
Configuration for Drive 3 (Working drive EVE S XCR):
vendor_id: 0x0000029c
product_id: 0x03b31001
auto_fault_reset: true
rpdo:
- index: 0x1600
channels:
- {index: 0x6040, sub_index: 0, type: uint16, command_interface: control_word}
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position}
- {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity}
- {index: 0x6060, sub_index: 0, type: int8, command_interface: mode_of_operation, default: 8}
- {index: 0x6071, sub_index: 0, type: int16, command_interface: effort}
tpdo:
- index: 0x1a00
channels:
- {index: 0x6041, sub_index: 0, type: uint16, state_interface: status_word}
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position, factor: 0.0000002396844981}
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity, factor: 0.0001256637061}
- {index: 0x6061, sub_index: 0, type: int8, state_interface: mode_of_operation}
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort}
Below is the ros2_control EtherCAT configuration:
<ros2_control name="ec_single_axis" type="system">
<hardware>
<plugin>ethercat_driver/EthercatDriver</plugin>
<param name="master_id">0</param>
<param name="control_frequency">1000</param>
</hardware>
<joint name="${name}_HAA">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="position">
<param name="min">"${haa_min_count}"</param>
<param name="max">"${haa_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${haa_min_mrev_sec}" </param>
<param name="max">"${haa_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_1">
<plugin>ethercat_generic_plugins/EcCiA402Drive</plugin>
<param name="alias">0</param>
<param name="position">0</param>
<param name="mode_of_operation">8</param>
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_1c.yaml</param>
</ec_module>
</joint>
<joint name="${name}_HFE">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="position">
<param name="min">"${hfe_min_count}"</param>
<param name="max">"${hfe_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${hfe_min_mrev_sec}" </param>
<param name="max">"${hfe_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_2">
<plugin>ethercat_generic_plugins/EcCiA402Drive</plugin>
<param name="alias">0</param>
<param name="position">1</param>
<param name="mode_of_operation">8</param>
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_2c.yaml</param>
</ec_module>
</joint>
<joint name="${name}_KFE">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="position">
<param name="min">"${kfe_min_count}"</param>
<param name="max">"${kfe_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${kfe_min_mrev_sec}" </param>
<param name="max">"${kfe_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_1">
<plugin>ethercat_generic_plugins/EcCiA402Drive</plugin>
<param name="alias">0</param>
<param name="position">2</param>
<param name="mode_of_operation">8</param>
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param>
</ec_module>
</joint>
</ros2_control>
My setup is based on Ubuntu 22.04 and ROS2 Rolling.
I've attached the dmesg output obtained with EtherCAT debug level set to 1 for both scenarios (with and without the 0x6060 register).
the output from ros2 for the first scenario is:
[INFO] [launch]: All log files can be found below /home/lab/.ros/log/2024-10-07-13-20-27-556845-lab-X570-AORUS-PRO-1754316
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [1754335]
[INFO] [robot_state_publisher-2]: process started with pid [1754337]
[INFO] [spawner-3]: process started with pid [1754339]
[INFO] [spawner-4]: process started with pid [1754341]
[robot_state_publisher-2] [INFO] [1728300027.781726491] [robot_state_publisher]: Robot initialized
[ros2_control_node-1] [WARN] [1728300027.787804042] [controller_manager]: [Deprecated] Passing the robot description parameter directly to the control_manager node is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead.
[ros2_control_node-1] [INFO] [1728300027.787959145] [resource_manager]: Loading hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.789292642] [resource_manager]: Initialize hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.789513276] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300027.791563557] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300027.792113448] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300027.792629878] [EthercatDriver]: Got 3 modules
[ros2_control_node-1] [INFO] [1728300027.792639488] [resource_manager]: Successful initialization of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.792739280] [resource_manager]: 'configure' hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.792742820] [resource_manager]: Successful 'configure' of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.792746681] [resource_manager]: 'activate' hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300027.792749211] [EthercatDriver]: Starting ...please wait...
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6040, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x607a, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6071, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6060, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6041, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6064, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x606c, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6077, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6061, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6040, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x607a, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6071, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6060, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6041, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6064, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x606c, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6077, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6061, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6040, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x607a, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6071, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6060, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6041, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6064, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x606c, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6077, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6061, 0x0}
[ros2_control_node-1] [INFO] [1728300027.793665469] [EthercatDriver]: Activated EcMaster!
[ros2_control_node-1] 4 slave(s).
[ros2_control_node-1] Master AL states: 0x02.
[ros2_control_node-1] Link is up.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] [INFO] [1728300028.793936625] [EthercatDriver]: updated!
[ros2_control_node-1] [INFO] [1728300028.793966966] [EthercatDriver]: System Successfully started!
[ros2_control_node-1] [INFO] [1728300028.793977926] [resource_manager]: Successful 'activate' of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300028.797481686] [controller_manager]: update rate is 1000 Hz
[ros2_control_node-1] [WARN] [1728300028.797540387] [controller_manager]: Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT scheduling. See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details.
[ros2_control_node-1] [INFO] [1728300028.830893662] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1728300028.838196588] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1728300028.838753069] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1728300028.838802080] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1728300028.846580915] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ros2_control_node-1] [INFO] [1728300028.854602644] [controller_manager]: Loading controller 'forward_position_controller'
[spawner-4] [INFO] [1728300028.860292478] [spawner_forward_position_controller]: Loaded forward_position_controller
[ros2_control_node-1] [INFO] [1728300028.861003422] [controller_manager]: Configuring controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1728300028.861440281] [forward_position_controller]: configure successful
[ros2_control_node-1] [INFO] [1728300028.862676176] [forward_position_controller]: activate successful
[spawner-4] [INFO] [1728300028.864230787] [spawner_forward_position_controller]: Configured and activated forward_position_controller
[ros2_control_node-1] Slave: State 0x01.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Domain: WC 3.
[ros2_control_node-1] Domain: State 1.
[ros2_control_node-1] STATE: Fault with status word :1560
[INFO] [spawner-3]: process has finished cleanly [pid 1754339]
[INFO] [spawner-4]: process has finished cleanly [pid 1754341]
[ros2_control_node-1] Slave: State 0x04.
[ros2_control_node-1] Slave: State 0x01.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Domain: WC 6.
[ros2_control_node-1] STATE: Fault with status word :1560
[ros2_control_node-1] Slave: State 0x04.
[ros2_control_node-1] Slave: State 0x01.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Domain: WC 9.
[ros2_control_node-1] Domain: State 2.
[ros2_control_node-1] Slave: State 0x04.
[ros2_control_node-1] STATE: Fault with status word :5656
[ros2_control_node-1] Master AL states: 0x0E.
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
The output from ros2 for second scenario (without x6060) is:
[INFO] [launch]: All log files can be found below /home/lab/.ros/log/2024-10-07-13-24-39-278208-lab-X570-AORUS-PRO-1758210
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [1758220]
[INFO] [robot_state_publisher-2]: process started with pid [1758222]
[INFO] [spawner-3]: process started with pid [1758224]
[INFO] [spawner-4]: process started with pid [1758226]
[robot_state_publisher-2] [INFO] [1728300279.504662735] [robot_state_publisher]: Robot initialized
[ros2_control_node-1] [WARN] [1728300279.510317613] [controller_manager]: [Deprecated] Passing the robot description parameter directly to the control_manager node is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead.
[ros2_control_node-1] [INFO] [1728300279.510507547] [resource_manager]: Loading hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.511804534] [resource_manager]: Initialize hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.511998058] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300279.514183793] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300279.514732845] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1728300279.515253836] [EthercatDriver]: Got 3 modules
[ros2_control_node-1] [INFO] [1728300279.515263916] [resource_manager]: Successful initialization of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.515372158] [resource_manager]: 'configure' hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.515376178] [resource_manager]: Successful 'configure' of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.515379858] [resource_manager]: 'activate' hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300279.515382408] [EthercatDriver]: Starting ...please wait...
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6040, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x607a, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6071, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6041, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6064, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x606c, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6077, 0x0}
[ros2_control_node-1] {0, 0, 0x29c, 0x2c30001, 0x6061, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6040, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x607a, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6071, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6041, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6064, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x606c, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6077, 0x0}
[ros2_control_node-1] {0, 1, 0x29c, 0x2c31001, 0x6061, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6040, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x607a, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x60ff, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6071, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6060, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6041, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6064, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x606c, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6077, 0x0}
[ros2_control_node-1] {0, 2, 0x29c, 0x3b31001, 0x6061, 0x0}
[ros2_control_node-1] [INFO] [1728300279.516150554] [EthercatDriver]: Activated EcMaster!
[ros2_control_node-1] 4 slave(s).
[ros2_control_node-1] Master AL states: 0x02.
[ros2_control_node-1] Link is up.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Slave: online.
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] [INFO] [1728300280.516692270] [EthercatDriver]: updated!
[ros2_control_node-1] [INFO] [1728300280.516718850] [EthercatDriver]: System Successfully started!
[ros2_control_node-1] [INFO] [1728300280.516728511] [resource_manager]: Successful 'activate' of hardware 'ec_single_axis'
[ros2_control_node-1] [INFO] [1728300280.520593511] [controller_manager]: update rate is 1000 Hz
[ros2_control_node-1] [WARN] [1728300280.520670382] [controller_manager]: Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT scheduling. See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details.
[ros2_control_node-1] Domain: WC 3.
[ros2_control_node-1] Domain: State 1.
[ros2_control_node-1] STATE: Fault with status word :1560
[ros2_control_node-1] [INFO] [1728300280.652741673] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1728300280.661549216] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1728300280.662111448] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1728300280.662173569] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1728300280.669453371] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ros2_control_node-1] [INFO] [1728300280.673585577] [controller_manager]: Loading controller 'forward_position_controller'
[spawner-4] [INFO] [1728300280.679462130] [spawner_forward_position_controller]: Loaded forward_position_controller
[ros2_control_node-1] [INFO] [1728300280.680107143] [controller_manager]: Configuring controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1728300280.680632364] [forward_position_controller]: configure successful
[ros2_control_node-1] [INFO] [1728300280.681855009] [forward_position_controller]: activate successful
[spawner-4] [INFO] [1728300280.683515944] [spawner_forward_position_controller]: Configured and activated forward_position_controller
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
[ros2_control_node-1] Domain: WC 6.
[ros2_control_node-1] STATE: Fault with status word :1560
[INFO] [spawner-3]: process has finished cleanly [pid 1758224]
[INFO] [spawner-4]: process has finished cleanly [pid 1758226]
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
[ros2_control_node-1] Slave: State 0x01.
[ros2_control_node-1] Slave: State 0x02.
[ros2_control_node-1] Domain: WC 9.
[ros2_control_node-1] Domain: State 2.
[ros2_control_node-1] Slave: State 0x04.
[ros2_control_node-1] STATE: Fault with status word :5656
[ros2_control_node-1] Master AL states: 0x0A.
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
test_with.txt
test_without_6060.txt
Many thanks for your time
Best
Alessio