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
126 stars 32 forks source link

Unable to write position with EcCiA402Drive #67

Open IdoPractical opened 1 year ago

IdoPractical commented 1 year ago

Hello, I'm currently experiencing difficulties with the Leadshine DM3E-556 stepper motor driver (Chinese version, also known as EM3E-556). The driver allows me to read parameters like the Status Word and Mode of Operation, as shown in the attached image so I guess the EtherCAT connection is OK and I the PDOs are correct. However, I'm encountering issues when trying to write the position and control the motor. Despite using the position_controllers/JointGroupPositionController to send position commands, I'm not seeing any response. Any guidance or suggestions to resolve this problem would be greatly appreciated. Thank you!

image

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    position_controller:
      type: position_controllers/JointGroupPositionController

position_controller:
  ros__parameters:
    joints:
      - joint1
      - joint2
    interface_name: position
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:macro name="rrbot_modular_actuators" params="name prefix slowdown:=2.0">
    <ros2_control name="mySystem" type="system">
      <hardware>
        <plugin>ethercat_driver/EthercatDriver</plugin>
        <param name="master_id">0</param>
        <param name="control_frequency">100</param>
      </hardware>
    <joint name="joint1">
        <state_interface name="position"/>
        <state_interface name="velocity"/>
        <state_interface name="status.word"/>
        <state_interface name="m.o.o.display"/>
        <command_interface name="position"/>
        <command_interface name="velocity"/>
        <ec_module name="DM3E">
          <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">$(find ros2_control_demo_example_6)/urdf/DM3E_slave_config.yaml</param>
        </ec_module>
      </joint>
  </ros2_control>
  <ros2_control name="Demo" type="mock">
      <joint name="joint2">
        <plugin>mock_components/GenericSystem</plugin>
      </joint>
    </ros2_control>
  </xacro:macro>
</robot>

The part of EtherCAT from the launcher log

[ros2_control_node-1] Domain: WC 3.
[ros2_control_node-1] Domain: State 2.
[ros2_control_node-1] STATE: Switch on Disabled with status word :1648
[ros2_control_node-1] Master AL states: 0x08.
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
[ros2_control_node-1] STATE: Ready to Switch On with status word :1585
[ros2_control_node-1] STATE: Switch On with status word :1587
[ros2_control_node-1] STATE: Operation Enabled with status word :5687
mcbed commented 1 year ago

Hi @practical-mechanics, Your setup looks fine, what happens if you turn your motor by hand ? does the position change ?

IdoPractical commented 1 year ago

I can't turn the motor, it's kind of locked after the software enables it.

mcbed commented 1 year ago

It looks like the controller did not launch as it expects to find joint2 which is not declared in your urdf as mock is not a valid type. Try removing joint2 from urdf and controller yaml file. Also check the state of the controller ros2 control list_controllers if it is active

IdoPractical commented 1 year ago

I already removed joint2 when trying to get it working. This is the output of the list_controllers command:

joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active    
forward_position_controller[forward_command_controller/ForwardCommandController] active    

And the log of the launch file:

INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [7828]
[INFO] [robot_state_publisher-2]: process started with pid [7830]
[INFO] [spawner-3]: process started with pid [7832]
[robot_state_publisher-2] [INFO] [1686055417.492645916] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1686055417.492885690] [robot_state_publisher]: got segment link1
[robot_state_publisher-2] [INFO] [1686055417.492908158] [robot_state_publisher]: got segment link2
[robot_state_publisher-2] [INFO] [1686055417.492921347] [robot_state_publisher]: got segment world
[ros2_control_node-1] [INFO] [1686055417.515355916] [resource_manager]: Loading hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686055417.537200869] [resource_manager]: Initialize hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686055417.537720822] [EthercatDriver]: joints
[ros2_control_node-1] channel 24640: missing channel info
[ros2_control_node-1] channel 24698: missing channel info
[ros2_control_node-1] channel 24760: missing channel info
[ros2_control_node-1] [INFO] [1686055417.550662784] [EthercatDriver]: Got 1 modules
[ros2_control_node-1] [INFO] [1686055417.550697619] [resource_manager]: Successful initialization of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686055417.550922812] [resource_manager]: 'configure' hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686055417.550940214] [resource_manager]: Successful 'configure' of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686055417.550968447] [resource_manager]: 'activate' hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686055417.550981263] [EthercatDriver]: Starting ...please wait...
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6040, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x607a, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60b8, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x603f, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6041, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6061, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6064, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60b9, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60ba, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60fd, 0x0}
[ros2_control_node-1] [INFO] [1686055417.552354415] [EthercatDriver]: Activated EcMaster!
[ros2_control_node-1] 3 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] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] [INFO] [1686055418.552661088] [EthercatDriver]: updated!
[ros2_control_node-1] [INFO] [1686055418.552735451] [EthercatDriver]: System Successfully started!
[ros2_control_node-1] [INFO] [1686055418.552749875] [resource_manager]: Successful 'activate' of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686055418.561296979] [controller_manager]: update rate is 100 Hz
[ros2_control_node-1] [WARN] [1686055418.562271779] [controller_manager]: Could not enable FIFO RT scheduling policy
[ros2_control_node-1] [INFO] [1686055418.703528468] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1686055418.723839320] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1686055418.725317217] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1686055418.725491860] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1686055418.753888639] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[INFO] [spawner-3]: process has finished cleanly [pid 7832]
[INFO] [spawner-4]: process started with pid [7901]
[ros2_control_node-1] Domain: WC 3.
[ros2_control_node-1] Domain: State 2.
[ros2_control_node-1] STATE: Switch on Disabled with status word :1616
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
[ros2_control_node-1] STATE: Ready to Switch On with status word :1585
[ros2_control_node-1] STATE: Switch On with status word :1587
[ros2_control_node-1] Master AL states: 0x0A.
[ros2_control_node-1] STATE: Operation Enabled with status word :5687
[ros2_control_node-1] [INFO] [1686055421.191906354] [controller_manager]: Loading controller 'forward_position_controller'
[spawner-4] [INFO] [1686055421.203841242] [spawner_forward_position_controller]: Loaded forward_position_controller
[ros2_control_node-1] [INFO] [1686055421.205200286] [controller_manager]: Configuring controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1686055421.206237110] [forward_position_controller]: configure successful
[ros2_control_node-1] [INFO] [1686055421.212470886] [forward_position_controller]: activate successful
[spawner-4] [INFO] [1686055421.223502257] [spawner_forward_position_controller]: Configured and activated forward_position_controller
[INFO] [spawner-4]: process has finished cleanly [pid 7901]
mcbed commented 1 year ago

then it may be a configuration issue:

[ros2_control_node-1] channel 24640: missing channel info -> control word
[ros2_control_node-1] channel 24698: missing channel info -> target position 
[ros2_control_node-1] channel 24760: missing channel info -> Touch probe function

can you paste your DM3E_slave_config.yaml ?

IdoPractical commented 1 year ago

then it may be a configuration issue:

[ros2_control_node-1] channel 24640: missing channel info -> control word
[ros2_control_node-1] channel 24698: missing channel info -> target position 
[ros2_control_node-1] channel 24760: missing channel info -> Touch probe function

can you paste your DM3E_slave_config.yaml ?

Sure. It took me some time to get it working without getting a rejection from the drive... This is the last version I came up with:

vendor_id: 0x00004321
product_id: 0x00008100
# rpdo:
#   - index: 0x1600
#     channels:
#       - {index: 0x6040, sub-index: 0, type: uint16} # Control Word
#       - {index: 0x607a, sub-index: 0, type: uint32, command-interface: position} # Target Position
#       - {index: 0x60b8, sub-index: 0, type: uint16, default: 0} # Touch Probe Function
# rpdo2:
#   - index: 0x1601
#     channels:
#       - {index: 0x6040, sub-index: 0, type: uint16} # Control Word
#       - {index: 0x607a, sub-index: 0, type: int32, command_interface: position, default: .nan} # Target Position
#       - {index: 0x6081, sub-index: 0, type: uint32} # Max Profile velocity
#       - {index: 0x6083, sub-index: 0, type: int32, default: 50} # Profile Acceleration
#       - {index: 0x6084, sub-index: 0, type: uint32, default: 50} # Profile Deceleration
#       - {index: 0x6060, sub-index: 0, type: int8, default: 8} # Modes Of Operation
rpdo:
  - index: 0x1600
    channels:
      - {index: 0x6040, sub-index: 0, type: uint16} # Control Word
      - {index: 0x607a, sub-index: 0, type: int32, command_interface: position, default: .nan} # Target Position
      - {index: 0x60b8, sub-index: 0, type: uint16}

tpdo:  # TxPDO 
  - index: 0x1a00
    channels:
      - {index: 0x603F, sub_index: 0, type: uint16, state_interface: last.error.code}
      - {index: 0x6041, sub_index: 0, type: uint16, state_interface: status.word}
      - {index: 0x6061, sub_index: 0, type: uint8, state_interface: m.o.o.display}
      - {index: 0x6064, sub_index: 0, type: uint32, state_interface: position}
      - {index: 0x60B9, sub_index: 0, type: uint16}
      - {index: 0x60BA, sub_index: 0, type: uint32}
      - {index: 0x60FD, sub_index: 0, type: uint32, state_interface: digital.inputs}
      # - {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity}
sm:  # Sync Manager
  - {index: 3, type: input, pdo: tpdo, watchdog: disable}
  - {index: 2, type: output, pdo: rpdo, watchdog: disable}

And the manual can be found here under the downloads section

mcbed commented 1 year ago

It seems there is a typo in your configuration of rpdo : sub-index -> sub_index

IdoPractical commented 1 year ago

It seems there is a typo in your configuration of rpdo : sub-index -> sub_index

Thank you. I fixed the typo but still can't get it to work. The controllers are active and I can see the status word etc.

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [28940]
[INFO] [robot_state_publisher-2]: process started with pid [28942]
[INFO] [spawner-3]: process started with pid [28944]
[robot_state_publisher-2] [INFO] [1686645215.099559240] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1686645215.099716284] [robot_state_publisher]: got segment link1
[robot_state_publisher-2] [INFO] [1686645215.099738957] [robot_state_publisher]: got segment link2
[robot_state_publisher-2] [INFO] [1686645215.099750453] [robot_state_publisher]: got segment world
[ros2_control_node-1] [INFO] [1686645215.122185809] [resource_manager]: Loading hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686645215.127912929] [resource_manager]: Initialize hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686645215.129696270] [EthercatDriver]: joints
[ros2_control_node-1] [INFO] [1686645215.134799373] [EthercatDriver]: Got 1 modules
[ros2_control_node-1] [INFO] [1686645215.135558409] [resource_manager]: Successful initialization of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686645215.136269049] [resource_manager]: 'configure' hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686645215.136804466] [resource_manager]: Successful 'configure' of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686645215.137330200] [resource_manager]: 'activate' hardware 'mySystem' 
[ros2_control_node-1] [INFO] [1686645215.137914893] [EthercatDriver]: Starting ...please wait...
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6040, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x607a, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60b8, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6060, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x603f, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6041, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6061, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x6064, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60b9, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60ba, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x60fd, 0x0}
[ros2_control_node-1] {0, 0, 0x4321, 0x8100, 0x606c, 0x0}
[ros2_control_node-1] [INFO] [1686645215.139100874] [EthercatDriver]: Activated EcMaster!
[ros2_control_node-1] 3 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] STATE: Not Ready to Switch On with status word :0
[ros2_control_node-1] [INFO] [1686645216.139368072] [EthercatDriver]: updated!
[ros2_control_node-1] [INFO] [1686645216.139401362] [EthercatDriver]: System Successfully started!
[ros2_control_node-1] [INFO] [1686645216.139413934] [resource_manager]: Successful 'activate' of hardware 'mySystem'
[ros2_control_node-1] [INFO] [1686645216.153583731] [controller_manager]: update rate is 100 Hz
[ros2_control_node-1] [WARN] [1686645216.154595925] [controller_manager]: Could not enable FIFO RT scheduling policy
[ros2_control_node-1] [INFO] [1686645216.334417251] [controller_manager]: Loading controller 'joint_state_broadcaster'
[spawner-3] [INFO] [1686645216.345970461] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1686645216.347068122] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1686645216.347296890] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-3] [INFO] [1686645216.366064213] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[INFO] [spawner-3]: process has finished cleanly [pid 28944]
[INFO] [spawner-4]: process started with pid [29011]
[ros2_control_node-1] Domain: WC 3.
[ros2_control_node-1] Domain: State 2.
[ros2_control_node-1] STATE: Switch on Disabled with status word :1648
[ros2_control_node-1] Slave: State 0x08.
[ros2_control_node-1] Slave: operational.
[ros2_control_node-1] STATE: Ready to Switch On with status word :1585
[ros2_control_node-1] STATE: Switch On with status word :1587
[ros2_control_node-1] Master AL states: 0x0A.
[ros2_control_node-1] STATE: Operation Enabled with status word :5687
[ros2_control_node-1] [INFO] [1686645218.807793583] [controller_manager]: Loading controller 'forward_position_controller'
[spawner-4] [INFO] [1686645218.826093126] [spawner_forward_position_controller]: Loaded forward_position_controller
[ros2_control_node-1] [INFO] [1686645218.827340440] [controller_manager]: Configuring controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1686645218.828586890] [forward_position_controller]: configure successful
[ros2_control_node-1] [INFO] [1686645218.834788857] [forward_position_controller]: activate successful
[spawner-4] [INFO] [1686645218.846078973] [spawner_forward_position_controller]: Configured and activated forward_position_controller
[INFO] [spawner-4]: process has finished cleanly [pid 29011]
mcbed commented 1 year ago

Did you try sending position goals using SDO Mailboxing ? You can find some information here

IdoPractical commented 1 year ago

I tried now but I get an error when writing (both on operation modes 1 and 8), I can read values without any problems. image

mcbed commented 1 year ago

What about kernel logs when doing this ? To see these logs containing additional information about the EtherCAT master:

  1. set ethercat master debug mode $ ethercat debug 1
  2. get logs $ sudo dmesg
dpflexvn commented 3 months ago

Hello mcbed, I have same problem, so I ask here, not create new "issue". I summarize my system:

yguel commented 3 months ago

Hi dpflexvn, In the ec_jmc_config.yaml (here ec_jmc_config.txt) the sync manager informations are commented. Can-you try the sm part de-commented like below:

# Configuration file for JASD7502 (Just Motion Control) drive

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false  # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo:  # sdo data to be transferred at drive startup
  - {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms
  - {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s
rpdo:  # RxPDO = receive PDO Mapping
  - index: 0x1600
    channels:
      - {index: 0x6040, sub_index: 0, type: uint16, default: 0}  # Control word
      - {index: 0x6060, sub_index: 0, type: int8, default: 8}  # Mode of operation
      - {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan}  # Target position
      - {index: 0x60b8, sub_index: 0, type: uint16, default: 0}  # Touch probe function
      - {index: 0x60fe, sub_index: 1, type: int32, default: 0}  # Physical outputs
      - {index: 0x60fe, sub_index: 2, type: uint32, default: 0}  # bit mask
tpdo:  # TxPDO = transmit PDO Mapping
  - index: 0x1a00
    channels:
      - {index: 0x603f, sub_index: 0, type: uint16}  # Error code
      - {index: 0x6041, sub_index: 0, type: uint16}  # Status word
      - {index: 0x6061, sub_index: 0, type: int8}  # Mode of operation display
      - {index: 0x6064, sub_index: 0, type: int32, state_interface: position}  # Position actual value
      - {index: 0x60b9, sub_index: 0, type: uint16}  # Touch_probe_status
      - {index: 0x60ba, sub_index: 0, type: int32}  # Touch_probe_pos1_pos_value
      - {index: 0x60bb, sub_index: 0, type: int32}  # Touch_probe_pos1_neg_value
      - {index: 0x60bc, sub_index: 0, type: int32}  # Touch_probe_pos2_pos_value
      - {index: 0x60bd, sub_index: 0, type: int32}  # Touch_probe_pos2_neg_value
      - {index: 0x60fd, sub_index: 0, type: int32}  # digtal_inputs
sm:
  - {index: 0, type: output, pdo:~, watchdog: disable}
  - {index: 1, type: input, pdo:~, watchdog: disable}
  - {index: 2, type: output, pdo: rpdo, watchdog: disable}
  - {index: 3, type: input, pdo: tpdo, watchdog: disable}

Could you also provide the output of the ethercat kernel module in debug mode ?

  1. set ethercat master debug mode $ ethercat debug 1
  2. get logs $ sudo tail -f /var/log/{dmesg,syslog} | grep -i ethercat
dpflexvn commented 3 months ago

Hi yguel, Thank you for quick response. I had commented sync manager because it had error :) I followed your advice and upload 3 test options, hope it is useful to you. Thank you.

ethercat_kernel_debug_3.txt ethercat_kernel_debug_2.txt ethercat_kernel_debug_1.txt

yguel commented 3 months ago

This error message looks very interesting:

EtherCAT ERROR 0 0:0: PDO entry 0x6040:00 is not mapped.

I would like to have more information about your drive:

dpflexvn commented 3 months ago

Hello, Please download from drive, it is too big to upload here.

  1. ESI file: https://drive.google.com/file/d/1ZbTa8fv9Vf3lQF9K9tP86k13ad_2tXhh/view?usp=sharing
  2. Manual: https://drive.google.com/file/d/1MqQajCZv5u5OqpR2Nxj0btbEM8sZyamC/view?usp=drive_link
  3. Datasheet/Brochure: https://drive.google.com/file/d/1SQUFXt0x89JBkw7wovBKe5Tiv4wvh99T/view?usp=drive_link Thank you.
yguel commented 3 months ago

Hi dpflexvn, There is an error, this is not the ESI file that is pointed by your link but the yaml config file of the ethercat_driver_ros2 library. For the datasheet/Brochure, this is in Chinese and I am sorry, but I cannot read Chinese. I could use an automatic translation tool, but I am not confident in the output.

The Manual is ok and I can definitely use it.

dpflexvn commented 3 months ago

Hi yguel, Sorry, I copied wrong link. Here is ESI link: https://drive.google.com/file/d/1yplGh2bPUa29Cb8EALF35UnQJM7CrFog/view?usp=sharing About brochure/datasheet, I only have Chinese version :) Be honest, I guess most of information in it. Thank you.

yguel commented 3 months ago

Based on the manual I can propose you the 4 following configuration files. You just have to use one of them or build one that suits you based upon them. I explain to you how to build the file: you have to use the object dictionary at pages 317-324 (336-343 of the pdf), and especially PDO mapping (the rows with a Y in the 7th column) that are at pages 321-324 (340-343 of the pdf).

Then you have to choose one of the 4 rpdo buffers (index 0x1600 or 0x1601 or 0x1602 or 0x1603) and one of the 4 tpdo buffers (index 0x1a00 or 0x1a01 or 0x1a02 or 0x1a03), with the limitation that they can only store 48 octets.

For an entry in the object dictionary, if you make any mistake about the index, sub_index or type it won't work.

Custom config close to the epos3 of ICube laboratory

# Configuration file for JASD7502 (Just Motion Control) drive
# Using object dictionary from JASD7502 manual pages 317-324 (336-343 of the pdf),
# PDO mapping are in pages 321-324 (340-343 of the pdf).

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
  - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
  - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO = receive PDO Mapping, 48 octets max, custom mapping 2+1+4+4+2+4+4+2+2+4+4 = 33 octets
  - index: 0x1600
    channels:
      - { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
      - { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
      - {
          index: 0x607a,
          sub_index: 0,
          type: int32,
          command_interface: position,
          default: .nan,
        } # Target position
      - {
          index: 0x60FF,
          sub_index: 0,
          type: int32,
          command_interface: velocity,
          default: .nan,
        } # Target velocity
      - {
          index: 0x6071,
          sub_index: 0,
          type: int16,
          command_interface: torque,
          default: .nan,
        } # Target torque
      - { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position
      - { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity
      - { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque
      - { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch probe  function
      - { index: 0x60fe, sub_index: 1, type: uint32, default: 0 } # Digital outputs
      - { index: 0x60fe, sub_index: 2, type: uint32, default: 0 } # Output bit mask
tpdo: # TxPDO = transmit PDO Mapping, 48 octets max, custom mapping, 2+4+4+2+1+4+2+4+4+4+4 = 31 octets
  - index: 0x1a00
    channels:
      - { index: 0x6041, sub_index: 0, type: uint16 } # Status word
      - { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Current position
      - { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Current velocity
      - { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Current torque
      - { index: 0x6061, sub_index: 0, type: int8 } # Current operation mode
      - { index: 0x60fd, sub_index: 1, type: uint32 } # Digital Inputs
      - { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
      - { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive Value (rising edge)
      - { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative Value (falling edge)
      - { index: 0x60bc, sub_index: 0, type: int32 } # Touch probe position 2 positive value (rising edge)
      - { index: 0x60bd, sub_index: 0, type: int32 } # Touch probe position 2 negative value (falling edge)

Config for position corresponding to the 0th default config of the manual (position)

# Configuration file for JASD7502 (Just Motion Control) drive
# Using object dictionary from JASD7502 manual pages 317-324 (336-343 of the pdf),
# PDO mapping are in pages 321-324 (340-343 of the pdf).

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
  - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
  - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO0 = receive PDO Mapping 0, 48 octets max, default mapping (page 271-272 of JASD7502 manual) 2+1+4+2+4+4 = 17 octets
  - index: 0x1600
    channels:
      - { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
      - { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
      - {
          index: 0x607a,
          sub_index: 0,
          type: int32,
          command_interface: position,
          default: .nan,
        } # Target position
      - { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch probe  function
      - { index: 0x60fe, sub_index: 1, type: uint32, default: 0 } # Digital outputs
      - { index: 0x60fe, sub_index: 2, type: uint32, default: 0 } # Output bit mask
tpdo: # TxPDO0 = transmit PDO Mapping 0, 48 octets max, custom mapping, default mapping (page 271-272 of JASD7502 manual), 2+4+2+4+4+4+4+4 = 28 octets
  - index: 0x1a00
    channels:
      - { index: 0x6041, sub_index: 0, type: uint16 } # Status word
      - { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Current position
      - { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
      - { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive Value (rising edge)
      - { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative Value (falling edge)
      - { index: 0x60bc, sub_index: 0, type: int32 } # Touch probe position 2 positive value (rising edge)
      - { index: 0x60bd, sub_index: 0, type: int32 } # Touch probe position 2 negative value (falling edge)
      - { index: 0x60fd, sub_index: 1, type: uint32 } # Digital Inputs

Config for position corresponding to the 1st default config of the manual (velocity)

# Configuration file for JASD7502 (Just Motion Control) drive
# Using object dictionary from JASD7502 manual pages 317-324 (336-343 of the pdf),
# PDO mapping are in pages 321-324 (340-343 of the pdf).

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
  - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
  - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO1 = receive PDO Mapping 1, 48 octets max, default mapping (page 271-272 of JASD7502 manual) 2+1+4+2+4+4 = 17 octets
  - index: 0x1601
    channels:
      - { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
      - { index: 0x6060, sub_index: 0, type: int8, default: 9 } # Mode of operation
      - {
          index: 0x60FF,
          sub_index: 0,
          type: int32,
          command_interface: velocity,
          default: .nan,
        } # Target velocity
      - { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch probe  function
      - { index: 0x60fe, sub_index: 1, type: uint32, default: 0 } # Digital outputs
      - { index: 0x60fe, sub_index: 2, type: uint32, default: 0 } # Output bit mask
tpdo: # TxPDO1 = transmit PDO Mapping 1, 48 octets max, custom mapping, default mapping (page 271-272 of JASD7502 manual), 1+4+4 = 9 octets
  - index: 0x1a01
    channels:
      - { index: 0x6061, sub_index: 0, type: int8 } # Current operation mode
      - { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Current velocity
      - { index: 0x60f4, sub_index: 0, type: int32 } # Tracking error for position

Config for position corresponding to the 2nd default config of the manual (torque)

# Configuration file for JASD7502 (Just Motion Control) drive
# Using object dictionary from JASD7502 manual pages 317-324 (336-343 of the pdf),
# PDO mapping are in pages 321-324 (340-343 of the pdf).

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
  - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
  - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO2 = receive PDO Mapping 2, 48 octets max, default mapping (page 271-272 of JASD7502 manual) 2+4+4+4+4+4 = 22 octets
  - index: 0x1602
    channels:
      - {
          index: 0x6071,
          sub_index: 0,
          type: int16,
          command_interface: torque,
          default: .nan,
        } # Target torque
      - { index: 0x6081, sub_index: 0, type: uint32, default: 0 } # Contour speed
      - { index: 0x6083, sub_index: 0, type: uint32, default: 0 } # Contour acceleration
      - { index: 0x6084, sub_index: 0, type: uint32, default: 0 } # Contour deceleration
      - { index: 0x60fe, sub_index: 1, type: uint32, default: 0 } # Digital outputs
      - { index: 0x60fe, sub_index: 2, type: uint32, default: 0 } # Output bit mask
tpdo: # TxPDO2 = transmit PDO Mapping 2, 48 octets max, custom mapping, default mapping (page 271-272 of JASD7502 manual), 2+2 = 4 octets
  - index: 0x1a02
    channels:
      - { index: 0x603f, sub_index: 0, type: uint16 } # Error code
      - { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Current torque

Config for position corresponding to the 3rd default config of the manual (homing)

# Configuration file for JASD7502 (Just Motion Control) drive
# Using object dictionary from JASD7502 manual pages 317-324 (336-343 of the pdf),
# PDO mapping are in pages 321-324 (340-343 of the pdf).

vendor_id: 0x66668888
product_id: 0x20199307
assign_activate: 0x0300 #0x003c # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
  - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
  - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO3 = receive PDO Mapping 3, 48 octets max, default mapping (page 271-272 of JASD7502 manual) 4+1+4+4+4 = 17 octets
  - index: 0x1603
    channels:
      - { index: 0x607c, sub_index: 0, type: int32, default: 0 } # Zero offset
      - { index: 0x6098, sub_index: 0, type: int8, default: 0 } # Direction of homing
      - { index: 0x6099, sub_index: 1, type: uint32, default: 0 } # Speed to mechanical origin
      - { index: 0x6099, sub_index: 2, type: uint32, default: 0 } # Speed for homing (zero offset)
      - { index: 0x609a, sub_index: 0, type: uint32, default: 0 } # Acceleration for homing (zero offset)
tpdo: # TxPDO = transmit PDO Mapping, 48 octets max, custom mapping, 2+4+4+2+1+4+2+4+4+4+4 = 31 octets
  - index: 0x1a00
    channels:
      - { index: 0x6041, sub_index: 0, type: uint16 } # Status word
      - { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Current position
      - { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Current velocity
      - { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Current torque
      - { index: 0x6061, sub_index: 0, type: int8 } # Current operation mode
      - { index: 0x60fd, sub_index: 1, type: uint32 } # Digital Inputs
      - { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
      - { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive Value (rising edge)
      - { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative Value (falling edge)
      - { index: 0x60bc, sub_index: 0, type: int32 } # Touch probe position 2 positive value (rising edge)
      - { index: 0x60bd, sub_index: 0, type: int32 } # Touch probe position 2 negative value (falling edge)

Tell-me if they work.

dpflexvn commented 3 months ago

Hi yguel, Thank you so much for your effort to check data and advise me. Unfortunately it could not work. I tried all of your options.

I tried other option:

And here is output of terminal & debug: ec_jmc_debug_2024_03_27.txt ec_jmc_terminal_output_2024_03_27.txt ec_jmc_xml_exported.txt

Just FYI: I tried the same method with Leadshine servo drive (chinese brand name, too), it has same error :)

yguel commented 3 months ago

I see some problems: you miss some elements when you checked the types, for instance your state_interface and command_interface have type uint32 whereas it must be int32. Could you just test one of the files I provided to you (for instance the 0th default as this is a configuration provided by JMC) ?

  1. If this does not work send me the debug output for this one if it does not work.
  2. If it works, then recheck thoroughly your config file to be sure you did not miss any problem with index, sub_index and type.

P.S. if you want to include a yaml file in this discussion, just use the following syntax: ```yaml your yaml code ```

dpflexvn commented 3 months ago

Hi yguel, Of course, I tried your suggestion first. It was failed, so I tried another. I use "unit32" instead of "int32" because it is in "xml" file which is release by "ethercat xml" command. I assume that the manual is not updated. Anyway, please receive debug of the option: "Config for position corresponding to the 0th default config of the manual (position)". I just copy&paste your yaml file, and checked again carefully, so I do not paste here again :) ec_jmc_debug_yguel_2024_03-27.txt ec_jmc_terminal_output_yguel_2024_03-27.txt

yguel commented 3 months ago

Hi dpflexvn, When you use:

ethercat xml

it does not provides you with something defined by the JMC motor controller, but with the config of the igh ethercat master. However this is one of the purposes of the ethercat_driver_ros2 library to configure the igh ethercat master. So maybe what has happened is that you have configured the ethercat master with ethercat_driver_ros2 with a faulty yaml config file, then read the configuration back. You can check that by stopping your ROS2 program, restarting the ethercat master and just running the ethercat xml command. As nothing will be configured, you will see that almost nothing will be in the result apart from a few basic information about the slaves.

However it does not tell us yet why it did not work with a simple example.

If, however, you have used an other software (like one provided by JMC, if any) to setup the ethercat master and if with that setup the drives work correctly, and then you have run the ethercat xml command then the output could be considered as accurate. In that case effectively the documentation and the ESI file would be obsolete. However it would be very curious that a variable like the target position would be unsigned, especially because it would not allow you to setup the zero wherever you need it. It would also probably violate the cia402 norm that the manual says the motor controller should follow, since that standard allows for zero setup.

yguel commented 3 months ago

Dear dpflexvn, I see some warnings, but no error in any of the 2 files you provided for the 0th default config.

Can you describe more what you expect to see, since the message: 71 (ros2_control_node-1] STATE: Operation Enabled with status word :5687 looks good

In the kernel driver debug logs, it looks that some datagram are skipped, so some frames are lost. This is not very good, but may have a lot of origin not related to the ethercat_driver_ros2 configuration. Also, the sync warning 'Slave did not sync after 5000ms' may tell us something is to be investigated there.

Can you try to change the parameter: auto_fault_reset: false to true and see what happens ?

dpflexvn commented 3 months ago

Hi yguel, Wao, you shared lot of info, I need time to absorb it :)

dpflexvn commented 2 months ago

Hi yguel, Please receive my update:

I still do not know why I cannot control drive by command :) Can you advise ?. Tks.