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

Handle transmission gear configuration #115

Closed willian-henrique closed 2 months ago

willian-henrique commented 2 months ago

Hi,

I'm currently developing a project utilizing the ethercat_driver_ros2 driver, where I'm integrating a motor with a gear ratio of 200:1. I've attempted to configure this setup following the guidelines outlined in the URDF Transmission specification (https://wiki.ros.org/urdf/XML/Transmission), but unfortunately, I haven't been successful.

After researching related discussions, such as the one on https://github.com/ros-controls/ros2_control/issues/798, I've come to understand that the implementation for handling transmission gear ratios should be incorporated into the hardware driver. However, it appears that the current source code for ethercat_driver_ros2 doesn't include this functionality.

I'm curious to know if there are any plans or a schedule in place to implement this feature in the driver. It would greatly benefit my project, and I'm eager to hear about any updates or insights regarding its development.

Thank you!

yguel commented 2 months ago

Hi, I think there is a case here for debate. I think that what destogl was thinking is that if the gear ratio is fixed, a simple and logic way to take it into account is to modify what the position, velocity, etc. state and command are; to integrate it directly as an hardware interface. However, it can also be implemented in the controller side, especially if the gear ratio is not fixed and changing it, is part of the controller job. A very strong argument in favor of destogl, is that if it is integrated in the hardware interface, then you can use generic controllers. What we should actually need is chaining operations on the hardware interface (to actually mimic what happens on the hardware level: motor chained with gear box). However we can also chain controllers, so I there is a good case to use chain of controllers with one for the gear box.

So there is several avenues now for solving your problem:

  1. if you have to write your own controller, integrate the transmission parameters in it, it won't change your code a lot.
  2. you can extend the generic motor controller in the ethercat_driver_ros2 to integrate transmission parameters. I would be helping in that case. We have to work on the specification part first and fit it in our roadmap.
  3. you can use a chain of controllers and create a specific controller for the gear box (I can also be helping in this case, but I would like to also have the opinion of destogl on that, to be sure not missing a crucial point).

I should also mention that, if it was not done before in our part, it is because it was not needed. The reason is that we use motor drivers (epos) that integrate the gearbox configuration inside the motor driver. Those information may help you choose what is the most efficient course of action for you to integrate transmission configuration into your setup.

willian-henrique commented 2 months ago

@yguel Thanks for your attention.

I'm currently working with the EPOS driver and motors. I've attempted to configure them using SDO 0x3000 and other required configurations, but unfortunately, I haven't had success.

Even if I were to successfully configure them, I find it to be a peculiar solution for my application. I utilize controllers such as JointTrajectoryController and JointStateBroadcast, which interface in radians (position) and radians per second (velocity), whereas the EPOS operates in steps. Am I missing something? Is there a workaround for this?

The solution to implementing the gear in the controller doesn't seem viable for me because I'm using a ready-to-use controller (JointTrajectoryController and JointStateBroadcast).

Initially, I started developing a controller that should be chainable. However, I discovered that controllers inheriting from the ChainableControllerInterface class can't expose state; they can only publish commands. The implementation for this functionality is currently in development here. Once it's completed, I believe it will be feasible to implement a generic gear solution.

I'm already utilizing the ros2_canopen controller (https://github.com/ros-industrial/ros2_canopen), where they've implemented gear translation. Hence, I'm considering implementing it within the ethercat_driver_ros2 hardware component. I've developed a prototype code snippet as shown below:

hardware_interface::return_type EthercatDriver::read(
  const rclcpp::Time & /*time*/,
  const rclcpp::Duration & /*period*/)
{

  master_.readData();
  hw_joint_states_[0][0] = (double) hw_joint_states_[0][0]*0.002617;
  hw_joint_states_[0][1] = (double) hw_joint_states_[0][1]*0.002617;
  hw_joint_states_[0][2] = (double) hw_joint_states_[0][2]*0.002617;
  RCLCPP_INFO(
    rclcpp::get_logger("EthercatDriver"), "WILL - Read: %f", hw_joint_states_[0][0]);
  return hardware_interface::return_type::OK;
}

hardware_interface::return_type EthercatDriver::write(
  const rclcpp::Time & /*time*/,
  const rclcpp::Duration & /*period*/)
{
  hw_joint_commands_[0][0] = (double) hw_joint_commands_[0][0]*381.971863421;
  RCLCPP_INFO(
    rclcpp::get_logger("EthercatDriver"), "WILL - Write: %f", hw_joint_commands_[0][0]);

  master_.writeData();
  return hardware_interface::return_type::OK;
}

This is still in the early stages of development, primarily implemented to test whether the commands from Moveit are executed with the gear, which they are.

I'm unsure if I'm taking the best approach here. Any insights would be greatly appreciated. If you believe the gear should be implemented in the ethercat_driver_ros2, I'm willing to work on it.

yguel commented 2 months ago

Dear willian2005, For such a simple use (no dynamic gear ratio but a fixed static one), there already is a solution using the factor parameter of the ethercat channels. Here is an example for an EPOS3 drive where the position and velocity data are updated according to a gearbox connected to a linear screw with following parameters:

States and commands:

Note that you could also use the offset parameter to actually transform any channel read by the driver using a linear factor*x+offset relation.

# Configuration file for Maxon EPOS3 drive
vendor_id: 0x000000fb
product_id: 0x64400000
assign_activate: 0x0300 # DC Synch register
auto_fault_reset: true # 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, master (out) to slave (in) (MOSI)
  - index: 0x1603
    channels:
      - {
          index: 0x6040,
          sub_index: 0,
          type: uint16,
          command_interface: control_word,
          default: 0,
        } # Control word
      - {
          index: 0x607a,
          sub_index: 0,
          type: int32,
          command_interface: position,
          default: .nan,
          factor: 8769230.76923077,
          offset: 0.0
        } # Target position (input in m converted in counts)
      - {
          index: 0x60ff,
          sub_index: 0,
          type: int32,
          command_interface: velocity,
          default: 0,
          factor: 263076.92307692306,
          offset: 0.0
        } # Target velocity (input in m/s converted in rpm)
      - {
          index: 0x6071,
          sub_index: 0,
          type: int16,
          command_interface: effort,
          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,
          command_interface: mode_of_operation,
          default: 9,
        } # 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, slave (out) to master (in) (MISO)
  - index: 0x1a03
    channels:
      - {
          index: 0x6041,
          sub_index: 0,
          type: uint16,
          state_interface: status_word,
        } # Status word
      - { index: 0x6064, sub_index: 0, type: int32, state_interface: position
          factor: 1.1403508771929825e-07,
          offset: 0.0 } # Position actual value in m
      - { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity
          factor: 3.8011695906432747e-06,
          offset: 0.0 } # Velocity actual value in m/s
      - { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Torque actual value
      - {
          index: 0x6061,
          sub_index: 0,
          type: int8,
          state_interface: mode_of_operation,
        } # 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

For a dynamic change of the gearbox, we should transform the ethercat slave by modifying the fonctions you presented but using additional data. I have still to work on the specifications.

willian-henrique commented 2 months ago

Dear Yguel,

Thank you for providing the solution. I plan to test it out on Monday, and it appears to be fitting for my project, aligning well with the scenario you've described.

Following the test, I'll provide you with feedback.

Thanks again.

Best regards,

Willian Henrique

willian-henrique commented 2 months ago

Dear Yguel,

I'm pleased to report that the suggested configuration worked for me. Thank you for your assistance in resolving this issue.

I believe that we can proceed to close this issue.

Best regards,

Willian Henrique