Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

only can read state_interface, cannot write to command_interface #124

Open
gitzhangomc opened this issue Jun 2, 2024 · 5 comments
Open

Comments

@gitzhangomc
Copy link

My servo drive is a 1-to-3 type, with one ECAT slave controlling three servo motors. Currently, the ROS2 EtherCAT driver I configured can read all joints state_interface but cannot write to the command_interface. What could be the issue? This is my Ethercat slave configuration file:

Configuration file for Maxon EPOS3 drive

vendor_id: 0x00000748
product_id: 0x0000000B
assign_activate: 0x0300 # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
auto_state_transitions: true

rpdo: # RxPDO = receive PDO Mapping

  • 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: 0x6060, sub_index: 0, type: int8} # Mode of operation
    • {index: 0x27FE, sub_index: 0, type: uint8} # Dummy Byte
  • index: 0x1610
    channels:
    • {index: 0x6840, sub_index: 0, type: uint16} # Control word
    • {index: 0x687a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
    • {index: 0x6860, sub_index: 0, type: int8} # Mode of operation
    • {index: 0x2FFE, sub_index: 0, type: uint8} # Dummy Byte
  • index: 0x1620
    channels:
    • {index: 0x7040, sub_index: 0, type: uint16} # Control word
    • {index: 0x707a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
    • {index: 0x7060, sub_index: 0, type: int8} # Mode of operation
    • {index: 0x37FE, sub_index: 0, type: uint8} # Dummy Byte
      tpdo: # TxPDO = transmit PDO Mapping
  • index: 0x1a00
    channels:
    • {index: 0x6041, sub_index: 0, type: uint16} # Status word
    • {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
    • {index: 0x6077, sub_index: 0, type: int16, state_interface: torque} # Torque actual value
    • {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
    • {index: 0x27FF, sub_index: 0, type: uint8} # Dummy Byte
    • {index: 0x603F, sub_index: 0, type: uint16, default: 0} # Error Code
    • {index: 0x60F4, sub_index: 0, type: int32, default: 0} # Following Error Actual Value
  • index: 0x1a10
    channels:
    • {index: 0x6841, sub_index: 0, type: uint16} # Status word
    • {index: 0x6864, sub_index: 0, type: int32, state_interface: position} # Position actual value
    • {index: 0x6877, sub_index: 0, type: int16, state_interface: torque} # Torque actual value
    • {index: 0x6861, sub_index: 0, type: int8} # Mode of operation display
    • {index: 0x2FFF, sub_index: 0, type: uint8} # Dummy Byte
    • {index: 0x683F, sub_index: 0, type: uint16, default: 0} # Error Code
    • {index: 0x68F4, sub_index: 0, type: int32, default: 0} # Following Error Actual Value
  • index: 0x1a20
    channels:
    • {index: 0x7041, sub_index: 0, type: uint16} # Status word
    • {index: 0x7064, sub_index: 0, type: int32, state_interface: position} # Position actual value
    • {index: 0x7077, sub_index: 0, type: int16, state_interface: torque} # Torque actual value
    • {index: 0x7061, sub_index: 0, type: int8} # Mode of operation display
    • {index: 0x37FF, sub_index: 0, type: uint8} # Dummy Byte
    • {index: 0x703F, sub_index: 0, type: uint16, default: 0} # Error Code
    • {index: 0x70F4, sub_index: 0, type: int32, default: 0} # Following Error Actual Value
@wei1224hf
Copy link

1600 and 1a00 , these 2 channels are enough , delete others
1a00 is TPDO mapping ,not rpdo,
your yaml config file is wrong ,

@wei1224hf
Copy link

here is the right format :

`

Configuration file for Maxon EPOS3 drive

vendor_id: 0x000000fb
product_id: 0x64400000
assign_activate: 0x0300 # 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: 0x1603
    channels:
    • {index: 0x6040, sub_index: 0, type: uint16, default: 0} # Control word
    • {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
    • {index: 0x60ff, sub_index: 0, type: int32, default: 0} # Target velocity
    • {index: 0x6071, sub_index: 0, type: int16, default: 0} # 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: 0x6060, sub_index: 0, type: int8, default: 8} # Mode of operation
    • {index: 0x2078, sub_index: 1, type: uint16, default: 0} # Digital Output Functionalities
    • {index: 0x60b8, sub_index: 0, type: uint16, default: 0} # Touch Probe Function
      tpdo: # TxPDO = transmit PDO Mapping
  • index: 0x1a03
    channels:
    • {index: 0x6041, sub_index: 0, type: uint16} # Status word
    • {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
    • {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value
    • {index: 0x6077, sub_index: 0, type: int16, state_interface: effort} # Torque actual value
    • {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
    • {index: 0x2071, sub_index: 1, type: int16} # Digital Input Functionalities State
    • {index: 0x60b9, sub_index: 0, type: int16} # Touch Probe Status
    • {index: 0x60ba, sub_index: 0, type: int32} # Touch Probe Position 1 Positive Value
    • {index: 0x60bb, sub_index: 0, type: int32} # Touch Probe Position 1 Negative Value
      `

@gaiyi7788
Copy link

I have a similar confusion. Because in a one-to-many slave, each motor has a corresponding address to control the quantities position and speed respectively. If the command_interface has the same name, I don't know which motor to control.

@dpflexvn
Copy link

Hi @gitzhangomc ,
I think you should try with 1 servo motor first.
I tried with EtherCAT 1.5.2 & Tsino Dynatron, but same issue as you. I will try EtherCAT 1.6 in next week and share.
What is your OS ?. kernel version ? ROS version ?.

@JensVanhooydonck
Copy link
Contributor

You could try to add 3 different config files.
one with index: 0x1600 and 0x1a00, one with 0x1610 and 0x1a10 and the last one with 0x1620 and 0x1a20.
So you can select the config file for one specific joint.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants