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

About one slave controlling multiple motors #127

Closed gaiyi7788 closed 5 months ago

gaiyi7788 commented 5 months ago

Thank you for your outstanding work!

I'm trying to apply this framework to my project. My slave is an adapter board for Ethercat communication to 6-way CAN communication.

What I'm wondering is, in the framework of ethercat_driver_ros2, does a joint have to correspond to a slave? If not, how should I adjust the slave_config file? Here is my slave_config file. With the initialization code, the slave can successfully enter the OP state.

vendor_id: 0x00000002      
product_id: 0x00060000
assign_activate: 0x0300 
auto_fault_reset: false 

rpdo:  # rxpdo = receive pdo mapping
  - index: 0x1600 # "outputs process data mapping"
    channels:
      - {index: 0x7000, sub_index: 0x01, type: int16, command_interface: control_cmd, default: 0}  # control_cmd

      - {index: 0x7000, sub_index: 0x02, type: int32, command_interface: position_target_1, default: 0}
      - {index: 0x7000, sub_index: 0x03, type: int32, command_interface: velocity_target_1, default: 0}
      - {index: 0x7000, sub_index: 0x04, type: int32, command_interface: torque_target_1, default: 0}
      - {index: 0x7000, sub_index: 0x05, type: int32, command_interface: kp_1, default: 0}
      - {index: 0x7000, sub_index: 0x06, type: int32, command_interface: kd_1, default: 0}

      - {index: 0x7000, sub_index: 0x07, type: int32, command_interface: position_target_2, default: 0}
      - {index: 0x7000, sub_index: 0x08, type: int32, command_interface: velocity_target_2, default: 0}
      - {index: 0x7000, sub_index: 0x09, type: int32, command_interface: torque_target_2, default: 0}
      - {index: 0x7000, sub_index: 0x0a, type: int32, command_interface: kp_2, default: 0}
      - {index: 0x7000, sub_index: 0x0b, type: int32, command_interface: kd_2, default: 0}

      - {index: 0x7000, sub_index: 0x0c, type: int32, command_interface: position_target_3, default: 0}
      - {index: 0x7000, sub_index: 0x0d, type: int32, command_interface: velocity_target_3, default: 0}
      - {index: 0x7000, sub_index: 0x0e, type: int32, command_interface: torque_target_3, default: 0}
      - {index: 0x7000, sub_index: 0x0f, type: int32, command_interface: kp_3, default: 0}
      - {index: 0x7000, sub_index: 0x10, type: int32, command_interface: kd_3, default: 0}

      - {index: 0x7000, sub_index: 0x11, type: int32, command_interface: position_target_4, default: 0}
      - {index: 0x7000, sub_index: 0x12, type: int32, command_interface: velocity_target_4, default: 0}
      - {index: 0x7000, sub_index: 0x13, type: int32, command_interface: torque_target_4, default: 0}
      - {index: 0x7000, sub_index: 0x14, type: int32, command_interface: kp_4, default: 0}
      - {index: 0x7000, sub_index: 0x15, type: int32, command_interface: kd_4, default: 0}

      - {index: 0x7000, sub_index: 0x16, type: int32, command_interface: position_target_5, default: 0}
      - {index: 0x7000, sub_index: 0x17, type: int32, command_interface: velocity_target_5, default: 0}
      - {index: 0x7000, sub_index: 0x18, type: int32, command_interface: torque_target_5, default: 0}
      - {index: 0x7000, sub_index: 0x19, type: int32, command_interface: kp_5, default: 0}
      - {index: 0x7000, sub_index: 0x1a, type: int32, command_interface: kd_5, default: 0}

      - {index: 0x7000, sub_index: 0x1b, type: int32, command_interface: position_target_6, default: 0}
      - {index: 0x7000, sub_index: 0x1c, type: int32, command_interface: velocity_target_6, default: 0}
      - {index: 0x7000, sub_index: 0x1d, type: int32, command_interface: torque_target_6, default: 0}
      - {index: 0x7000, sub_index: 0x1e, type: int32, command_interface: kp_6, default: 0}
      - {index: 0x7000, sub_index: 0x1f, type: int32, command_interface: kd_6, default: 0}
tpdo:  # txpdo = transmit pdo mapping
  - index: 0x1a00
    channels:
      - {index: 0x6000, sub_index: 0x01, type: int16, state_interface: motor_num}  # motor_num

      - {index: 0x6000, sub_index: 0x02, type: int16, state_interface: motor_id_1}  
      - {index: 0x6000, sub_index: 0x03, type: int16, state_interface: state_1}     
      - {index: 0x6000, sub_index: 0x04, type: int32, state_interface: position_actual_1}  
      - {index: 0x6000, sub_index: 0x05, type: int32, state_interface: velocity_actual_1}  
      - {index: 0x6000, sub_index: 0x06, type: int32, state_interface: torque_actual_1} 

      - {index: 0x6000, sub_index: 0x07, type: int16, state_interface: motor_id_2}  
      - {index: 0x6000, sub_index: 0x08, type: int16, state_interface: state_2}     
      - {index: 0x6000, sub_index: 0x09, type: int32, state_interface: position_actual_2} 
      - {index: 0x6000, sub_index: 0x0a, type: int32, state_interface: velocity_actual_2}  
      - {index: 0x6000, sub_index: 0x0b, type: int32, state_interface: torque_actual_2} 

      - {index: 0x6000, sub_index: 0x0c, type: int16, state_interface: motor_id_3}  
      - {index: 0x6000, sub_index: 0x0d, type: int16, state_interface: state_3}     
      - {index: 0x6000, sub_index: 0x0e, type: int32, state_interface: position_actual_3} 
      - {index: 0x6000, sub_index: 0x0f, type: int32, state_interface: velocity_actual_3}  
      - {index: 0x6000, sub_index: 0x10, type: int32, state_interface: torque_actual_3} 

      - {index: 0x6000, sub_index: 0x11, type: int16, state_interface: motor_id_4}  
      - {index: 0x6000, sub_index: 0x12, type: int16, state_interface: state_4}     
      - {index: 0x6000, sub_index: 0x13, type: int32, state_interface: position_actual_4} 
      - {index: 0x6000, sub_index: 0x14, type: int32, state_interface: velocity_actual_4}  
      - {index: 0x6000, sub_index: 0x15, type: int32, state_interface: torque_actual_4} 

      - {index: 0x6000, sub_index: 0x16, type: int16, state_interface: motor_id_5}  
      - {index: 0x6000, sub_index: 0x17, type: int16, state_interface: state_5}     
      - {index: 0x6000, sub_index: 0x18, type: int32, state_interface: position_actual_5} 
      - {index: 0x6000, sub_index: 0x19, type: int32, state_interface: velocity_actual_5}  
      - {index: 0x6000, sub_index: 0x1a, type: int32, state_interface: torque_actual_5} 

      - {index: 0x6000, sub_index: 0x1b, type: int16, state_interface: motor_id_6}  
      - {index: 0x6000, sub_index: 0x1c, type: int16, state_interface: state_6}     
      - {index: 0x6000, sub_index: 0x1d, type: int32, state_interface: position_actual_6} 
      - {index: 0x6000, sub_index: 0x1e, type: int32, state_interface: velocity_actual_6}  
      - {index: 0x6000, sub_index: 0x1f, type: int32, state_interface: torque_actual_6} 

Looking forward to your reply!

JensVanhooydonck commented 5 months ago

I have a branch where i've added a for: "joint_name" parameter, this way you could add multiple actuators in one slave: https://github.com/JensVanhooydonck/ethercat_driver_ros2/tree/filter_config_file

The branch is a little bit behind tho..

gaiyi7788 commented 5 months ago

Thanks for your reply! I will have a try.