-
Notifications
You must be signed in to change notification settings - Fork 75
Open
Description
Environment
- OS: Ubuntu 22.04, PREEMPT_RT realtime-kernel
- ROS 2 Version: Humble
- servo motor: Raynen RS3E1
- Master: IGH EtherCAT Master 1.5.3, using e1000e driver
- Network card model: Intel Corporation 82574L Gigabit
- ethercat_driver_ros2 branch: main
- Bind a process to specific CPU cores (CPU core control).
Issues Description
- When testing five servo motors (configured in CSP mode) of a palletizing machine without using Intel NICs, shortly after sequentially starting the servo motors, the servo drives exhibit warnings of excessive synchronous cycle errors, causing abnormal motor operation. Related error messages are shown in the figure below:
Both at 100Hz and 1000Hz DC synchronization/control cycle frequencies, servo drives trigger warning errors.
- When using Intel NICs at 1000Hz DC synchronization/control frequency, all five servo motors operate stably after sequential startup with no warnings.
kernel log
However, at 100Hz configuration, synchronous cycle error warnings persist.
Multiple improvement attempts have failed. Suspect potential issues in the DC synchronization implementation within ethercat_driver_ros2
Config files
ethercat_motor_drive/config/controllers.yaml
controller_manager:
ros__parameters:
update_rate: 100 # Hz
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
palletizing_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
velocity_controller:
type: velocity_controllers/JointGroupVelocityController
effort_controller:
type: effort_controllers/JointGroupEffortController
palletizing_arm_controller:
ros__parameters:
command_interfaces:
- position
state_interfaces:
- position
joints:
- joint_revolute_1
- joint_revolute_2
- joint_revolute_3
- joint_revolute_4
- joint_revolute_5
velocity_controller:
ros__parameters:
joints:
- joint_revolute_1
- joint_revolute_2
- joint_revolute_3
- joint_revolute_4
- joint_revolute_5
effort_controller:
ros__parameters:
joints:
- joint_revolute_1
- joint_revolute_2
- joint_revolute_3
- joint_revolute_4
- joint_revolute_5
EtherCAT Slave configuration
# Configuration file for Raynen RS3E1_5R5L drive
vendor_id: 0x00000922
product_id: 0x00000c01
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 7 Mapping
- index: 0x1702
channels:
- { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
- {
index: 0x607a,
sub_index: 0,
type: int32,
command_interface: position,
factor: 320421222.9264523077,
offset: 39533790,
# offset: 0,
# default: .nan
default: 39533790
} # 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: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
- { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch Probe Function
- { index: 0x607f, sub_index: 0, type: uint32, default: 838860800 } # Max Profile Velocity
tpdo: # TxPDO = transmit PDO 9 Mapping
- index: 0x1b02
channels:
- { index: 0x603f, sub_index: 0, type: uint16 } # Error Code
- { index: 0x6041, sub_index: 0, type: uint16 } # Status word
- {
index: 0x6064,
sub_index: 0,
type: int32,
state_interface: position,
factor: 3.120891902436607e-9,
offset: -0.123380685083629
# offset: 0
} # Position 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: 0x60b9, sub_index: 0, type: uint16 } # Touch Probe Status
- { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe pos1 Pos Value
- { index: 0x60bc, sub_index: 0, type: int32 } # Touch Probe pos2 Pos Value
- { index: 0x60fd, sub_index: 0, type: uint32} # Digital Inputs
sm: # Sync Manager
- {index: 0, type: output, pdo: ~, watchdog: disable}
- {index: 1, type: input, pdo: ~, watchdog: disable}
- {index: 2, type: output, pdo: rpdo, watchdog: enable}
- {index: 3, type: input, pdo: tpdo, watchdog: disable}
ethercat_motor_drive/description/ros2_control/motor_drive.ros2_control.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="motor_drive">
<ros2_control name="motor_drive" type="system">
<hardware>
<plugin>ethercat_driver/EthercatDriver</plugin>
<param name="master_id">0</param>
<param name="control_frequency">100</param>
</hardware>
<joint name="joint_revolute_1">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<command_interface name="position"/>
<command_interface name="reset_fault"/>
<ec_module name="Raynen">
<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 ethercat_motor_drive)/config/joint1_raynen_rs3e1_5r5l_3rd_config.yaml</param>
</ec_module>
</joint>
<joint name="joint_revolute_2">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<command_interface name="position"/>
<command_interface name="reset_fault"/>
<ec_module name="Raynen">
<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">$(find ethercat_motor_drive)/config/joint2_raynen_rs3e1_7r6m_3rd_config.yaml</param>
</ec_module>
</joint>
<joint name="joint_revolute_3">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<command_interface name="position"/>
<command_interface name="reset_fault"/>
<ec_module name="Raynen">
<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">$(find ethercat_motor_drive)/config/joint3_raynen_rs3e1_2r8l_3rd_config.yaml</param>
</ec_module>
</joint>
<joint name="joint_revolute_4">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<command_interface name="position"/>
<command_interface name="reset_fault"/>
<ec_module name="Raynen">
<plugin>ethercat_generic_plugins/EcCiA402Drive</plugin>
<param name="alias">0</param>
<param name="position">3</param>
<param name="mode_of_operation">8</param>
<param name="slave_config">$(find ethercat_motor_drive)/config/joint4_raynen_rs3e1_1r6l_3rd_config.yaml</param>
</ec_module>
</joint>
<joint name="joint_revolute_5">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<command_interface name="position"/>
<command_interface name="reset_fault"/>
<ec_module name="Raynen">
<plugin>ethercat_generic_plugins/EcCiA402Drive</plugin>
<param name="alias">0</param>
<param name="position">4</param>
<param name="mode_of_operation">8</param>
<param name="slave_config">$(find ethercat_motor_drive)/config/joint5_raynen_rs3e1_1r6l_3rd_config.yaml</param>
</ec_module>
</joint>
</ros2_control>
</xacro:macro>
</robot>
Metadata
Metadata
Assignees
Labels
No labels