ICube-Robotics / ethercat_driver_ros2

Hardware Interface for EtherCAT module integration with ros2_control
https://icube-robotics.github.io/ethercat_driver_ros2/
Apache License 2.0
156 stars 44 forks source link

Configuration problem for Ingenia EVE XCR and EVE S XCR #147

Open iamdrfly opened 1 month ago

iamdrfly commented 1 month ago

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

ammaraljodah commented 1 month ago

Check few things like:

  1. Check the state if the drives ethercat slaves Are they all opertional
  2. If they are check the status word, and faluts, did the faluts clear, if not check why
  3. Are you sending the command to enable them, are you claiming the hardware interfaces correctly
iamdrfly commented 1 month ago

Hi @ammaraljodah, Thank you for your time,

  1. Only the third drive reaches the OP. The other two drives (first and second) become SAFEOP+E
  2. when I kill the ros2_ethercat all the drives switch to PREOP.
  3. maybe I am doing wrong but according to the documentation is not necessary to claim the hw interface to reach the OP. "After launching the well-configured drive, by default and without fault, motor drive module is brought automatically into the state OPERATION_ENABLED making it ready for use. Automatic transition is only enabled when the control_word command interface is either missing or set to NaN making it possible for the user to take control over the motor drive’s state machine by sending corresponding state transition values using the control_word command interface."

I have noticed that the problem can be caused by the PDO register

Do you have any suggestions?

Best Alessio

ammaraljodah commented 1 month ago

Don't worry about the hardware interface, you are right once it comes into OP it will enable automaticly. You have problem in configuration. What is the output of sudo dmesg | grep EtherCAT

iamdrfly commented 1 month ago

Hi @ammaraljodah,

many thanks for your support, attached the result of sudo dmesg -w (test_2.txt) and sudo dmesg | grep EtherCAT (test_1.txt). test_1.txt test_2.txt

The configuration files for the drives are equal for the pdo, only the vendor_id e product_id are different. To find these values I used the command ethercat slaves.

image

Best Alessio

ammaraljodah commented 1 month ago

You need to give the permission for the user. Ros control needs to set pre-emption for the process.

[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.

ammaraljodah commented 1 month ago

Do these settings https://github.com/ros2-realtime-demo/pendulum/blob/rolling/docs/real_time_linux.md

ammaraljodah commented 1 month ago

Drop the controller frequency to 100Hz in the urdf of the plugin and in the yaml of the ros2 control. Are you using preempt-rt kernel? If not, you should use it.

ammaraljodah commented 1 month ago

Also use native driver for your ethernet controller instead if the generic

iamdrfly commented 1 month ago

Hi @ammaraljodah,

You are right I am no using a rt patch kernel. Does it make any difference (the problem is related to the pdo config, i do not understand the correlation)?

Unfortunately, I have not an ethernet card compatible with the ones required by link, as you can see below:


lspci -vv | grep Ethernet
04:00.0 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
    Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
04:00.1 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
    Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
05:00.0 Ethernet controller: Intel Corporation I211 Gigabit Network Connection (rev 03)
0a:00.0 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
    Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
0a:00.1 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
    Subsystem: Intel Corporation Ethernet Server Adapter I350-T2

Now I will install the preempt patch and I will update you.

Many thanks Alessio

ammaraljodah commented 1 month ago

How you know it is PDO config, have you mapped them correctly??

ammaraljodah commented 1 month ago

You need to map the PDOs using a set of SDOs if your drive is having flexible PDOs

iamdrfly commented 1 month ago

Hi @ammaraljodah,

I have followed your suggestion to use rt kernel but it doesn't work, I have the same problems.

Yes, the pdo used in the config files should be fine. Here the sdo available for the ingenia drives sdo_map.txt (This file is obtained by using ethercat sdos -p 0)

Here the output of dmesg -w dmesg_rt.txt

Here the output of sudo dmesg | grep EtherCAT grep_dmesg.txt

I don't understand how I can control and move only one of the 3 drives, which are identical except for the product and vendor id.

Many thanks for your help

Best regards Alessio

ammaraljodah commented 1 month ago

You need to map the PDOs, currently you are not mapping any at all.

iamdrfly commented 1 month ago

Hi @ammaraljodah,

I'm not sure what you're referring to. I've set up the PDO configuration using the YAML files.

# 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}

What am I missing? Could you please be more clear?

Best Alessio

ammaraljodah commented 1 month ago

Is this servo drive has fixed mapping or flexible mapping? Are those PDOs the same as the fixed mapping?

iamdrfly commented 1 month ago

Sure! Here's the revised version with your additional details:

Hi @ammaraljodah,

Good question! I believe there are 4 predefined RPDOs and 4 predefined TPDOs (refer to page 44 of the Ingenia manual). However, when I power cycle the system and run ethercat cstruct in the terminal, all the PDOs show up as empty. If I run the ethercat cstructcommand after first launching of ethercat_driver_ros2, I can see the PDOs that I have configured.

Does this servo drive use fixed mapping or flexible mapping?

How can I verify this?

Are the current PDOs the same as the fixed mapping ones?

If the PDOs are present on the drive, I believe the ones I’m trying to set might be different from the predefined fixed mappings.

Bets Alessio

ammaraljodah commented 1 month ago

Do the flexible mapping to be sure

4.1.4.3 Mapping procedure The steps to configure the PDO mapping are (Example for setting the RPDO 1): Place the controller into NMT pre-operational. Destroy the PDO writing a 1 into the valid bit of SubIndex 0x01 of PDO communication parameter. (0x1400 RPDO1 - bit 31 of COB-ID used) Unmap all registers from PDO by setting SubIndex 0x00 to zero. (0x1600 RPDO1 mapping parameter). Modify mapping by changing the values in the corresponding SubIndexes. (0x1600 RPDO1 mapping parameter). Enable mapping by setting SubIndex 0x00 to the number of mapped objects. (0x1600 RPDO1 mapping parameter). Create PDO by setting a 0 into the valid bit of SubIndex 0x01 of PDO communication parameter. (0x1400 RPDO1 - bit 31 of COB-ID used

iamdrfly commented 1 month ago

Hi @ammaraljodah,

Could you explain how this is handled in ros2_ethercat? Isn't this process managed automatically by ros2_ethercat? I’m a bit confused—if it's not managed automatically, how is it possible that I can see the PDOs after the first launch?

Best regards, Alessio

ammaraljodah commented 1 month ago

Ok, what is the output of ethercat slaves

iamdrfly commented 1 month ago

Hi @ammaraljodah,

Results after switching the drives off and on again before running ros2_ethercat:

ec_sync_info_t slave_0_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 1

ec_sync_info_t slave_1_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 2

ec_sync_info_t slave_2_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 3

ec_sync_info_t slave_3_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };


After launching `ros2_ethercat`:

-output `ethercat slaves`:

0 65535:0 SAFEOP+ERROR E 0x0000029c:0x02c30001 1 65535:0 SAFEOP+ERROR E 0x0000029c:0x02c31001 2 65535:1 OP + 0x0000029c:0x03b31001 3 65535:0 PREOP + 0x0000029c:0x02c31001


- output `ethercat cstruct`:

/* Master 0, Slave 0

ec_pdo_entry_info_t slave_0_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };

ec_pdo_info_t slave_0_pdos[] = { {0x1600, 5, slave_0_pdo_entries + 0}, {0x1a00, 6, slave_0_pdo_entries + 5}, };

ec_sync_info_t slave_0_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_0_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_0_pdos + 1, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 1

ec_pdo_entry_info_t slave_1_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };

ec_pdo_info_t slave_1_pdos[] = { {0x1600, 5, slave_1_pdo_entries + 0}, {0x1a00, 6, slave_1_pdo_entries + 5}, };

ec_sync_info_t slave_1_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_1_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_1_pdos + 1, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 2

ec_pdo_entry_info_t slave_2_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };

ec_pdo_info_t slave_2_pdos[] = { {0x1600, 5, slave_2_pdo_entries + 0}, {0x1a00, 6, slave_2_pdo_entries + 5}, };

ec_sync_info_t slave_2_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_2_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_2_pdos + 1, EC_WD_DISABLE}, {0xff} };

/* Master 0, Slave 3

ec_sync_info_t slave_3_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };



As you can see, the PDOs are configured after the first launch of ros2_ethercat.
PS: I have 4 drives but only the first 3 I would like to move.

Best Regards
Alessio
ammaraljodah commented 1 month ago

You are not setting the alias and position correctly The ethercat slaves has this format:

<id>  <alias>:<position>  <device_state>  +  <device_name>

Your alias 65535 But the position is wrong some drives has the same position Try to change the alias and set the new alias for the drives

Ideally your bus be like 0 0:0 1 0:1 2 0:2 So the first drive has alias of 0 and position of 0 Second has alias of 0 and position 1. You can not have the same position for the same alias.

ammaraljodah commented 1 month ago

Are you using ethercat junction?

ammaraljodah commented 1 month ago
ethercat alias [ OPTIONS ] < ALIAS >
Write alias addresses .
Arguments :
ALIAS must be an unsigned 16 bit number . Zero means
removing an alias address .
If multiple slaves are selected , the -- force option
is required .
Command - specific options :
-- alias -a < alias >
-- position -p <pos > Slave selection . See the help of
the ’ slaves ’ command .
-- force -f Acknowledge writing aliases of
multiple slaves .
Numerical values can be specified either with decimal ( no
prefix ) , octal ( prefix ’0 ’) or hexadecimal ( prefix ’0x ’) base .
ammaraljodah commented 1 month ago

Make sure to change the alias and position accordingly in the urdf file

iamdrfly commented 1 month ago

Hi @ammaraljodah,

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:property name="haa_min_count" value="260" />
  <xacro:property name="haa_max_count" value="764" />
  <xacro:property name="haa_min_mrev_sec" value="-120000" />
  <xacro:property name="haa_max_mrev_sec" value="120000" />

  <xacro:property name="hfe_min_count" value="260" />
  <xacro:property name="hfe_max_count" value="764" />
  <xacro:property name="hfe_min_mrev_sec" value="-120000" />
  <xacro:property name="hfe_max_mrev_sec" value="120000" />

  <xacro:property name="kfe_min_count" value="260" />
  <xacro:property name="kfe_max_count" value="764" />
  <xacro:property name="kfe_min_mrev_sec" value="-120000" />
  <xacro:property name="kfe_max_mrev_sec" value="120000" />

  <!-- mode of operation = 8 position; 9 velocity -->

  <xacro:macro name="ethercat" params="name">

    <ros2_control name="ec_single_axis" type="system">
      <hardware>
        <plugin>ethercat_driver/EthercatDriver</plugin>
        <param name="master_id">0</param>
        <param name="control_frequency">100</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="control_word"/>
        <command_interface name="mode_of_operation"/>
        <command_interface name="reset_fault"/>
        <state_interface name="mode_of_operation"/>
        <state_interface name="status_word"/>
        <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="mode_of_operation">20</param> -->
          <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_1c.yaml</param>
          <!-- <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param> -->
        </ec_module>
      </joint>

      <joint name="${name}_HFE">
        <command_interface name="control_word"/>
        <command_interface name="mode_of_operation"/>
        <command_interface name="reset_fault"/>
        <state_interface name="mode_of_operation"/>
        <state_interface name="status_word"/>
        <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="mode_of_operation">20</param> -->
          <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_2c.yaml</param>
          <!-- <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param> -->
        </ec_module>
      </joint>

      <joint name="${name}_KFE">
        <command_interface name="control_word"/>
        <command_interface name="mode_of_operation"/>
        <command_interface name="reset_fault"/>
        <state_interface name="mode_of_operation"/>
        <state_interface name="status_word"/>
        <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="mode_of_operation">20</param> -->
          <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param>
        </ec_module>
      </joint>

    </ros2_control>

  </xacro:macro>

</robot>

As you can see the positions are all different only the aliases are different. I do not know why I have an alias of 65535, should it be 0?

I use an ethernet RJ45 couple, I have not an ethercat junction.

Best Alessio

ammaraljodah commented 1 month ago

The alias in urdf should match the one from the ethercat slaves command. Moreover you have position conflict, several drived has same position. You need to fix that. Use ethercat alias To change alias

ammaraljodah commented 1 month ago

Your urdf is 0:0 0:1 0:2 Your actual bus is 65535:0
65535:0
65535:1 65535:0

Remove the unused drive and make the actual bus match the urdf

iamdrfly commented 1 month ago

Hi @ammaraljodah, Many thanks =D

I have changed the alias and now the EtherCAT slaves output is:

0  0:0  PREOP  +  0x0000029c:0x02c30001
1  0:1  PREOP  +  0x0000029c:0x02c31001
2  0:2  PREOP  +  0x0000029c:0x03b31001

So now the positions and aliases are good. However, the first two drives do not work.

here the output from ros2: out_ros2.txt

here the output from dmesg -w: out_dmesg.txt

Many thanks for your time and help.

Best Alessio

ammaraljodah commented 1 month ago

Two drives time-out when master requested to put them in op mode. Can you try one drive on the bus and have one joint in the urdf see if it comes to OP by itself. Then swap it to the second drive, then third. We want to see if it is the drive issue or ros issue.

iamdrfly commented 1 month ago

Hi @ammaraljodah,

I have modified the URDF to include only one drive at a time. For the first drive I have also disconnected the other two drives from the Ethercat chain (I cannot disconnect them for the other cases) and connected the Controller for cia402 drives #61.

The result for the first drive:

0 0:0 SAFEOP+ERROR E 0x0000029c:0x02c30001

header:
  stamp:
    sec: 1729234507
    nanosec: 653545968
  frame_id: ''
dof_names:
- FL_HAA
drive_states:
- STATE_SWITCH_ON_DISABLED
modes_of_operation:
- MODE_UNDEFINED
status_words:
- 1616

The result for the second drive:

The result for the third drive:



Best 
Alessio
ammaraljodah commented 1 month ago

I belive it is a drive issue

[  676.231341] EtherCAT ERROR 0-0: Timeout while setting state OP.

If you take the third drive and connect it as first and disconnect everything else, it would come OP, please confirm. If that's the case, you would need to check what is wrong with the hardware of your first and second drive.

iamdrfly commented 1 month ago

Hi @ammaraljodah

I have removed the first 2 drives from the ethercat chain and here the results:

ros2: ros2_only3.txt

dmesg: dmesg_only_3.txt

/cia402/drive_states:

header:
  stamp:
    sec: 1729240612
    nanosec: 831927000
  frame_id: ''
dof_names:
- FL_KFE
drive_states:
- STATE_OPERATION_ENABLED
modes_of_operation:
- MODE_UNDEFINED
status_words:
- 1591

ethercat slaves: 0 0:0 OP + 0x0000029c:0x03b31001

Do you have a suggestion on what should I check? The only difference among drives is that the first two are EVE XCR while the last is EVE S XCR. All drives have the same firmware version. Should I check their firmware?

Best Alessio

Best Alessio

ammaraljodah commented 1 month ago

Device Id

iamdrfly commented 1 month ago

Hi @ammaraljodah,

May I ask if you could be clearer?

ammaraljodah commented 1 month ago

You might set it incorrectly in yaml, double check it. Otherwise, Do debug 1 and see the dmesg

ammaraljodah commented 1 month ago

Put drive 1(the xcr) on the bus, and disconnect every other drive. Update the urdf accordingly to have one drive Then Build you packages Don't start your ros launch yet Then ethercat debug 1 Then sudo dmesg -w | grep EtherCAT > mylog Then Start your node

iamdrfly commented 1 month ago

Hi @ammaraljodah,

They look good to me, from EtherCAT slaves:

0  0:0  PREOP         E  0x0000029c:0x02c30001
1  0:1  SAFEOP+ERROR  E  0x0000029c:0x02c31001
2  0:2  PREOP         +  0x0000029c:0x03b31001

My .yaml:

drive1:

vendor_id: 0x0000029c
product_id: 0x02c30001

drive2:

vendor_id: 0x0000029c
product_id: 0x02c31001

drive3:

vendor_id: 0x0000029c
product_id: 0x03b31001

Here the result of the test: mylog.txt

Best Alessio

ammaraljodah commented 1 month ago

Do the debug as in my last post and provide results

iamdrfly commented 1 month ago

Hi @ammaraljodah.

Here the result: mylog.txt

Best Alessio

ammaraljodah commented 1 month ago

You have this showing no default mapping

502.472388] EtherCAT DEBUG 0 0:0: Loading default mapping for PDO 0x1600.
[  502.472389] EtherCAT DEBUG 0 0:0: No default mapping found.

Other than that the driver was responding to the SDOs, then it timed out when master requests OP mode.

It is driver issue, you need to configure your driver and save the mapping using the software of the driver if there is one. Or, you write the SDOs to map the PDOs.

At this point all Troubleshooting should be on the driver side.

iamdrfly commented 1 month ago

HI @ammaraljodah,

In the driver software seems that it is not possible to map the PDO (I will try to investigate more). Therefore, I think that the only possible solution is to write the SDOs to map the PDOs. Do you know if it is possible with ethercat_driver_ros2? If so, do you have any example ? Or can you explain how to do ? If I add them to config.yaml where also the PDOs are defined ?

Many thanks Best Regards Alessio

ammaraljodah commented 1 month ago

Use Twincat to map the PDOs Then copy the startup SDOs that has been generated from the mapping. See this video: https://youtu.be/2R-GD2JqNWI?si=ETbKEnLDkqAYskOJ While you are in Twincat, I recommend you test the drive and enable and move motor to have independent check of your hardware, before coming to this library. In terms of the ros library The SDOs can be sent by adding them in the yaml

ammaraljodah commented 1 month ago

See this for how to send SDOs on startup https://github.com/ICube-Robotics/ethercat_driver_ros2_examples

ammaraljodah commented 1 month ago

https://github.com/ICube-Robotics/ethercat_driver_ros2_examples/blob/main/ethercat_motor_drive/config/maxon_epos3_config.yaml

iamdrfly commented 1 month ago

Hi @ammaraljodah,

If I understand correctly, I need to follow these steps

how ? Should I use wireshark or somenthing else?

am I missing something?

Best Alessio

ammaraljodah commented 1 month ago

In the startup tab in twincat you will see the list of sdo that has been generated from the mapping. Watch the video above at: 6:33

iamdrfly commented 1 month ago

Dear @ammaraljodah,

On Monday when I will be in lab I will try and I will update you here. Many thanks for your time,

Best Alessio

iamdrfly commented 1 month ago

Hi @ammaraljodah, I have followed the video and here is Twincat's sdo: Immagine 2024-10-21 094714

However, it is unclear to me how I should implement the sdo in the yaml.

I have tried:

sdo:
  - {index: 0x1600, sub_index: 0, type: uint32, value: 0x60400010}
  - {index: 0x1600, sub_index: 1, type: uint32, value: 0x607A0020}
  - {index: 0x1600, sub_index: 2, type: uint32, value: 0x60FF0020}
  - {index: 0x1600, sub_index: 3, type: uint32, value: 0x60600008}
  - {index: 0x1600, sub_index: 4, type: uint32, value: 0x60710010}

  - {index: 0x1a00, sub_index: 0, type: uint32, value: 0x60410010}
  - {index: 0x1a00, sub_index: 1, type: uint32, value: 0x60640020}
  - {index: 0x1a00, sub_index: 2, type: uint32, value: 0x606C0020}
  - {index: 0x1a00, sub_index: 3, type: uint32, value: 0x60610008}
  - {index: 0x1a00, sub_index: 4, type: uint32, value: 0x60770010}
  - {index: 0x1a00, sub_index: 5, type: uint32, value: 0x603F0010}

  - {index: 0x1C12, sub_index: 0, type: uint32, value: 0x1600}
  - {index: 0x1C13, sub_index: 0, type: uint32, value: 0x1A00} 

and I got:

Do you know what I am doing wrong with the sdo? I am not pretty sure about the subindex.

Best Alessio

ammaraljodah commented 1 month ago

The mapping seems odd. Try uploading your drive esi file to twincat and see the startup sdos.

ammaraljodah commented 1 month ago

This might help https://www.kollmorgen.com/en-us/developer-network/setup-ethercat-master-run-akd2g-%E2%80%9Cds402-cyclic-synchronous-position-mode%E2%80%9D