You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have a and I am trying to get it to work in CSP with a single drive. I want to be able to set set points through the ROS2 driver and move a motor. Here is my basic setup:
Kollmorgen AKD-P01207 motor drive
Ubuntu 22.04
ROS2 Humble
Various branches of the ethercat_driver_ros2 repository
I can get the drive moving through the Kollmorgen workbench so I know it is setup correctly on the electrical side.
I am using the 1.5.3 IGH ethercat master. To get error logs I have enabled ethercat debug 1 and I use the command sudo dmesg -T | grep EtherCAT to get the logs.
Issues:
When using the humble branch of the ethercat_driver_ros2 start up the ethercat_driver_ros2 I get the following:
The drive does not come up it goes into Safe Op + Error
The drive indicates a fault 706 which is defined by Kollmorgen as "Fieldbus Cyclic Setpoints Missing"
When using the humble branch of the ethercat_driver_ros2 and disabling the F706 on the AKD-P01207 we get the system into Op without error. Though this is in Op, unfortunately it I cannot actually get it into any sort of usable condition. I notice that the status word is always 592.
I have attempted to fix by manually setting the next state in on the terminal via ethercat -p0 --type uint16 download 0x6040 0 6 which briefly gets the system from 592 to 561 before going back to 592.
[ros2_control_node-1] STATE: Ready to Switch On with status word :561 [ros2_control_node-1] STATE: Switch on Disabled with status word :592
This was under the impression that I could get it running potentially by not running that specific error. Unfortunately did not work.
The text was updated successfully, but these errors were encountered:
I can see several possibilities for your problem, the first thing to do is to adjust the cycle time to be used on the driver. From what I've seen in the documentation, you need to modify registers 0x60C2, under index 0X1 and 0X2. To work at 100HZ (if the driver allows this, check the documentation): value 0x2 : 3, value 0x1 : 10 or value 0x2 : 2, value 0x1 : 1. You can change these values with an SDO request or integrate them directly into your configuration file:
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
Another possibility concerns clock synchronisation #154 . During initialisation, we noticed that the ros_control mechanism generated instabilities in the cycle time that could disrupt certain drivers. We are currently looking for a solution to this problem, which should be included in the next release.
A temporary solution would be, if the drive allows it, to work in free mode (by commenting in your configuration file the line assign_activate: 0x0300
Finally, to update a register in your PDO mapping, you need to declare a command interface (control_word in your case) in the configuration file and then use a gpio_controller. As register 0x6040 is in your PDO mapping, the value written by an SDO request is overwritten by the PDO value...
Best
Philippe
Setup:
I have a and I am trying to get it to work in CSP with a single drive. I want to be able to set set points through the ROS2 driver and move a motor. Here is my basic setup:
ethercat_driver_ros2
repositoryI can get the drive moving through the Kollmorgen workbench so I know it is setup correctly on the electrical side.
Here is the yaml config for the drive: kollmorgen_akd_1207.txt
Here is the xacro for the controllers: akd_single_drive.txt
I am using the 1.5.3 IGH ethercat master. To get error logs I have enabled
ethercat debug 1
and I use the commandsudo dmesg -T | grep EtherCAT
to get the logs.Issues:
When using the humble branch of the
ethercat_driver_ros2
start up the ethercat_driver_ros2 I get the following:Here is a log from that: single_akd_test_with_706_enabled.txt
And here is the output of the system in the terminal: single_akd_test_with_706_enabled_terminal.txt
When using the humble branch of the
ethercat_driver_ros2
and disabling the F706 on the AKD-P01207 we get the system into Op without error. Though this is in Op, unfortunately it I cannot actually get it into any sort of usable condition. I notice that the status word is always 592.Here is a log from that: single_akd_test_with_706_disabled.txt
Here is the terminal output: single_akd_test_with_706_disabled_terminal.txt
I have attempted to fix by manually setting the next state in on the terminal via
ethercat -p0 --type uint16 download 0x6040 0 6
which briefly gets the system from 592 to 561 before going back to 592.[ros2_control_node-1] STATE: Ready to Switch On with status word :561 [ros2_control_node-1] STATE: Switch on Disabled with status word :592
This was under the impression that I could get it running potentially by not running that specific error. Unfortunately did not work.
The text was updated successfully, but these errors were encountered: