Open iamdrfly opened 1 month ago
Check few things like:
Hi @ammaraljodah, Thank you for your time,
I have noticed that the problem can be caused by the PDO register
Do you have any suggestions?
Best Alessio
Don't worry about the hardware interface, you are right once it comes into OP it will enable automaticly. You have problem in configuration. What is the output of sudo dmesg | grep EtherCAT
Hi @ammaraljodah,
many thanks for your support, attached the result of sudo dmesg -w (test_2.txt) and sudo dmesg | grep EtherCAT (test_1.txt). test_1.txt test_2.txt
The configuration files for the drives are equal for the pdo, only the vendor_id e product_id are different. To find these values I used the command ethercat slaves.
Best Alessio
You need to give the permission for the user. Ros control needs to set pre-emption for the process.
[WARN] [1728300028.797540387] [controller_manager]: Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT scheduling. See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details.
Drop the controller frequency to 100Hz in the urdf of the plugin and in the yaml of the ros2 control. Are you using preempt-rt kernel? If not, you should use it.
Also use native driver for your ethernet controller instead if the generic
Hi @ammaraljodah,
You are right I am no using a rt patch kernel. Does it make any difference (the problem is related to the pdo config, i do not understand the correlation)?
Unfortunately, I have not an ethernet card compatible with the ones required by link, as you can see below:
lspci -vv | grep Ethernet
04:00.0 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
04:00.1 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
05:00.0 Ethernet controller: Intel Corporation I211 Gigabit Network Connection (rev 03)
0a:00.0 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
0a:00.1 Ethernet controller: Intel Corporation I350 Gigabit Network Connection (rev 01)
Subsystem: Intel Corporation Ethernet Server Adapter I350-T2
Now I will install the preempt patch and I will update you.
Many thanks Alessio
How you know it is PDO config, have you mapped them correctly??
You need to map the PDOs using a set of SDOs if your drive is having flexible PDOs
Hi @ammaraljodah,
I have followed your suggestion to use rt kernel but it doesn't work, I have the same problems.
Yes, the pdo used in the config files should be fine. Here the sdo available for the ingenia drives sdo_map.txt (This file is obtained by using ethercat sdos -p 0
)
Here the output of dmesg -w
dmesg_rt.txt
Here the output of sudo dmesg | grep EtherCAT
grep_dmesg.txt
I don't understand how I can control and move only one of the 3 drives, which are identical except for the product and vendor id.
Many thanks for your help
Best regards Alessio
You need to map the PDOs, currently you are not mapping any at all.
Hi @ammaraljodah,
I'm not sure what you're referring to. I've set up the PDO configuration using the YAML files.
# Configuration file for Ingenia EVE-XCR-E drive
vendor_id: 0x0000029c
product_id: 0x02c30001
auto_fault_reset: true
tpdo:
- index: 0x1a00
channels:
- {index: 0x6041, sub_index: 0, type: uint16, state_interface: status_word}
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position, factor: 0.0000001198422491}
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity, factor: 0.00006283185307}
- {index: 0x6061, sub_index: 0, type: int8, state_interface: mode_of_operation}
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort}
rpdo:
- index: 0x1600
channels:
- {index: 0x6040, sub_index: 0, type: uint16, command_interface: control_word}
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position}
- {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity}
- {index: 0x6060, sub_index: 0, type: int8, command_interface: mode_of_operation, default: 8}
- {index: 0x6071, sub_index: 0, type: int16, command_interface: effort}
What am I missing? Could you please be more clear?
Best Alessio
Is this servo drive has fixed mapping or flexible mapping? Are those PDOs the same as the fixed mapping?
Sure! Here's the revised version with your additional details:
Hi @ammaraljodah,
Good question! I believe there are 4 predefined RPDOs and 4 predefined TPDOs (refer to page 44 of the Ingenia manual). However, when I power cycle the system and run ethercat cstruct
in the terminal, all the PDOs show up as empty.
If I run the ethercat cstruct
command after first launching of ethercat_driver_ros2, I can see the PDOs that I have configured.
Does this servo drive use fixed mapping or flexible mapping?
How can I verify this?
Are the current PDOs the same as the fixed mapping ones?
If the PDOs are present on the drive, I believe the ones I’m trying to set might be different from the predefined fixed mappings.
Bets Alessio
Do the flexible mapping to be sure
4.1.4.3 Mapping procedure The steps to configure the PDO mapping are (Example for setting the RPDO 1): Place the controller into NMT pre-operational. Destroy the PDO writing a 1 into the valid bit of SubIndex 0x01 of PDO communication parameter. (0x1400 RPDO1 - bit 31 of COB-ID used) Unmap all registers from PDO by setting SubIndex 0x00 to zero. (0x1600 RPDO1 mapping parameter). Modify mapping by changing the values in the corresponding SubIndexes. (0x1600 RPDO1 mapping parameter). Enable mapping by setting SubIndex 0x00 to the number of mapped objects. (0x1600 RPDO1 mapping parameter). Create PDO by setting a 0 into the valid bit of SubIndex 0x01 of PDO communication parameter. (0x1400 RPDO1 - bit 31 of COB-ID used
Hi @ammaraljodah,
Could you explain how this is handled in ros2_ethercat? Isn't this process managed automatically by ros2_ethercat? I’m a bit confused—if it's not managed automatically, how is it possible that I can see the PDOs after the first launch?
Best regards, Alessio
Ok, what is the output of ethercat slaves
Hi @ammaraljodah,
Results after switching the drives off and on again before running ros2_ethercat:
output of ethercat slaves
:
0 65535:0 PREOP + 0x0000029c:0x02c30001
1 65535:0 PREOP + 0x0000029c:0x02c31001
2 65535:1 PREOP + 0x0000029c:0x03b31001
3 65535:0 PREOP + 0x0000029c:0x02c31001
output of ethercat cstruct
:
/* Master 0, Slave 0
* Vendor ID: 0x0000029c
* Product code: 0x02c30001
* Revision number: 0x0005001f
*/
ec_sync_info_t slave_0_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 1
ec_sync_info_t slave_1_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 2
ec_sync_info_t slave_2_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 3
ec_sync_info_t slave_3_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };
After launching `ros2_ethercat`:
-output `ethercat slaves`:
0 65535:0 SAFEOP+ERROR E 0x0000029c:0x02c30001 1 65535:0 SAFEOP+ERROR E 0x0000029c:0x02c31001 2 65535:1 OP + 0x0000029c:0x03b31001 3 65535:0 PREOP + 0x0000029c:0x02c31001
- output `ethercat cstruct`:
/* Master 0, Slave 0
ec_pdo_entry_info_t slave_0_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };
ec_pdo_info_t slave_0_pdos[] = { {0x1600, 5, slave_0_pdo_entries + 0}, {0x1a00, 6, slave_0_pdo_entries + 5}, };
ec_sync_info_t slave_0_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_0_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_0_pdos + 1, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 1
ec_pdo_entry_info_t slave_1_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };
ec_pdo_info_t slave_1_pdos[] = { {0x1600, 5, slave_1_pdo_entries + 0}, {0x1a00, 6, slave_1_pdo_entries + 5}, };
ec_sync_info_t slave_1_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_1_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_1_pdos + 1, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 2
ec_pdo_entry_info_t slave_2_pdo_entries[] = { {0x6040, 0x00, 16}, {0x607a, 0x00, 32}, {0x60ff, 0x00, 32}, {0x6071, 0x00, 16}, {0x6060, 0x00, 8}, {0x6041, 0x00, 16}, {0x6064, 0x00, 32}, {0x606c, 0x00, 32}, {0x6077, 0x00, 16}, {0x6061, 0x00, 8}, {0x603f, 0x00, 16}, };
ec_pdo_info_t slave_2_pdos[] = { {0x1600, 5, slave_2_pdo_entries + 0}, {0x1a00, 6, slave_2_pdo_entries + 5}, };
ec_sync_info_t slave_2_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 1, slave_2_pdos + 0, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 1, slave_2_pdos + 1, EC_WD_DISABLE}, {0xff} };
/* Master 0, Slave 3
ec_sync_info_t slave_3_syncs[] = { {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}, {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {2, EC_DIR_OUTPUT, 0, NULL, EC_WD_ENABLE}, {3, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}, {0xff} };
As you can see, the PDOs are configured after the first launch of ros2_ethercat.
PS: I have 4 drives but only the first 3 I would like to move.
Best Regards
Alessio
You are not setting the alias and position correctly The ethercat slaves has this format:
<id> <alias>:<position> <device_state> + <device_name>
Your alias 65535 But the position is wrong some drives has the same position Try to change the alias and set the new alias for the drives
Ideally your bus be like 0 0:0 1 0:1 2 0:2 So the first drive has alias of 0 and position of 0 Second has alias of 0 and position 1. You can not have the same position for the same alias.
Are you using ethercat junction?
ethercat alias [ OPTIONS ] < ALIAS >
Write alias addresses .
Arguments :
ALIAS must be an unsigned 16 bit number . Zero means
removing an alias address .
If multiple slaves are selected , the -- force option
is required .
Command - specific options :
-- alias -a < alias >
-- position -p <pos > Slave selection . See the help of
the ’ slaves ’ command .
-- force -f Acknowledge writing aliases of
multiple slaves .
Numerical values can be specified either with decimal ( no
prefix ) , octal ( prefix ’0 ’) or hexadecimal ( prefix ’0x ’) base .
Make sure to change the alias and position accordingly in the urdf file
Hi @ammaraljodah,
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="haa_min_count" value="260" />
<xacro:property name="haa_max_count" value="764" />
<xacro:property name="haa_min_mrev_sec" value="-120000" />
<xacro:property name="haa_max_mrev_sec" value="120000" />
<xacro:property name="hfe_min_count" value="260" />
<xacro:property name="hfe_max_count" value="764" />
<xacro:property name="hfe_min_mrev_sec" value="-120000" />
<xacro:property name="hfe_max_mrev_sec" value="120000" />
<xacro:property name="kfe_min_count" value="260" />
<xacro:property name="kfe_max_count" value="764" />
<xacro:property name="kfe_min_mrev_sec" value="-120000" />
<xacro:property name="kfe_max_mrev_sec" value="120000" />
<!-- mode of operation = 8 position; 9 velocity -->
<xacro:macro name="ethercat" params="name">
<ros2_control name="ec_single_axis" type="system">
<hardware>
<plugin>ethercat_driver/EthercatDriver</plugin>
<param name="master_id">0</param>
<param name="control_frequency">100</param>
</hardware>
<joint name="${name}_HAA">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="control_word"/>
<command_interface name="mode_of_operation"/>
<command_interface name="reset_fault"/>
<state_interface name="mode_of_operation"/>
<state_interface name="status_word"/>
<command_interface name="position">
<param name="min">"${haa_min_count}"</param>
<param name="max">"${haa_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${haa_min_mrev_sec}" </param>
<param name="max">"${haa_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_1">
<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="mode_of_operation">20</param> -->
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_1c.yaml</param>
<!-- <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param> -->
</ec_module>
</joint>
<joint name="${name}_HFE">
<command_interface name="control_word"/>
<command_interface name="mode_of_operation"/>
<command_interface name="reset_fault"/>
<state_interface name="mode_of_operation"/>
<state_interface name="status_word"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="position">
<param name="min">"${hfe_min_count}"</param>
<param name="max">"${hfe_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${hfe_min_mrev_sec}" </param>
<param name="max">"${hfe_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_2">
<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="mode_of_operation">20</param> -->
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_2c.yaml</param>
<!-- <param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param> -->
</ec_module>
</joint>
<joint name="${name}_KFE">
<command_interface name="control_word"/>
<command_interface name="mode_of_operation"/>
<command_interface name="reset_fault"/>
<state_interface name="mode_of_operation"/>
<state_interface name="status_word"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<state_interface name="error_code"/>
<command_interface name="position">
<param name="min">"${kfe_min_count}"</param>
<param name="max">"${kfe_min_count}"</param>
</command_interface>
<command_interface name="velocity">
<param name="min">"${kfe_min_mrev_sec}" </param>
<param name="max">"${kfe_max_mrev_sec}"</param>
</command_interface>
<command_interface name="effort"/>
<command_interface name="reset_fault"/>
<ec_module name="drive_1">
<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="mode_of_operation">20</param> -->
<param name="slave_config">/home/lab/grace_ros2_ws/src/grace_description/config/driver_3b.yaml</param>
</ec_module>
</joint>
</ros2_control>
</xacro:macro>
</robot>
As you can see the positions are all different only the aliases are different. I do not know why I have an alias of 65535, should it be 0?
I use an ethernet RJ45 couple, I have not an ethercat junction.
Best Alessio
The alias in urdf should match the one from the ethercat slaves command. Moreover you have position conflict, several drived has same position. You need to fix that. Use ethercat alias To change alias
Your urdf is
0:0
0:1
0:2
Your actual bus is
65535:0
65535:0
65535:1
65535:0
Remove the unused drive and make the actual bus match the urdf
Hi @ammaraljodah, Many thanks =D
I have changed the alias and now the EtherCAT slaves output is:
0 0:0 PREOP + 0x0000029c:0x02c30001
1 0:1 PREOP + 0x0000029c:0x02c31001
2 0:2 PREOP + 0x0000029c:0x03b31001
So now the positions and aliases are good. However, the first two drives do not work.
here the output from ros2: out_ros2.txt
here the output from dmesg -w: out_dmesg.txt
Many thanks for your time and help.
Best Alessio
Two drives time-out when master requested to put them in op mode. Can you try one drive on the bus and have one joint in the urdf see if it comes to OP by itself. Then swap it to the second drive, then third. We want to see if it is the drive issue or ros issue.
Hi @ammaraljodah,
I have modified the URDF to include only one drive at a time. For the first drive I have also disconnected the other two drives from the Ethercat chain (I cannot disconnect them for the other cases) and connected the Controller for cia402 drives #61.
The result for the first drive:
0 0:0 SAFEOP+ERROR E 0x0000029c:0x02c30001
the output of ros2: out_ros2_first_drive.txt
the output of dmesg: dmesg_first_drive.txt
the /cia402/drive_states topic msg:
header:
stamp:
sec: 1729234507
nanosec: 653545968
frame_id: ''
dof_names:
- FL_HAA
drive_states:
- STATE_SWITCH_ON_DISABLED
modes_of_operation:
- MODE_UNDEFINED
status_words:
- 1616
The result for the second drive:
EtherCAT slaves
0 0:0 PREOP E 0x0000029c:0x02c30001
1 0:1 SAFEOP+ERROR E 0x0000029c:0x02c31001
2 0:2 PREOP + 0x0000029c:0x03b31001
dmesg dmesg_second_drive.txt
the /cia402/drive_states topic msg:
header:
stamp:
sec: 1729235767
nanosec: 472883875
frame_id: ''
dof_names:
FL_HFE drive_states:
STATE_SWITCH_ON_DISABLED modes_of_operation:
MODE_UNDEFINED status_words:
1616
The result for the third drive:
EtherCAT slaves
0 0:0 PREOP E 0x0000029c:0x02c30001
1 0:1 SAFEOP+ERROR E 0x0000029c:0x02c31001
2 0:2 OP + 0x0000029c:0x03b31001
dmesg dmesg_third_drive.txt
the /cia402/drive_states topic msg:
header:
stamp:
sec: 1729236252
nanosec: 7447392
frame_id: ''
dof_names:
FL_KFE drive_states:
STATE_OPERATION_ENABLED modes_of_operation:
MODE_UNDEFINED status_words:
1591
Best
Alessio
I belive it is a drive issue
[ 676.231341] EtherCAT ERROR 0-0: Timeout while setting state OP.
If you take the third drive and connect it as first and disconnect everything else, it would come OP, please confirm. If that's the case, you would need to check what is wrong with the hardware of your first and second drive.
Hi @ammaraljodah
I have removed the first 2 drives from the ethercat chain and here the results:
ros2: ros2_only3.txt
dmesg: dmesg_only_3.txt
/cia402/drive_states:
header:
stamp:
sec: 1729240612
nanosec: 831927000
frame_id: ''
dof_names:
- FL_KFE
drive_states:
- STATE_OPERATION_ENABLED
modes_of_operation:
- MODE_UNDEFINED
status_words:
- 1591
ethercat slaves:
0 0:0 OP + 0x0000029c:0x03b31001
Do you have a suggestion on what should I check? The only difference among drives is that the first two are EVE XCR while the last is EVE S XCR. All drives have the same firmware version. Should I check their firmware?
Best Alessio
Best Alessio
Device Id
Hi @ammaraljodah,
May I ask if you could be clearer?
You might set it incorrectly in yaml, double check it. Otherwise, Do debug 1 and see the dmesg
Put drive 1(the xcr) on the bus, and disconnect every other drive. Update the urdf accordingly to have one drive Then Build you packages Don't start your ros launch yet Then ethercat debug 1 Then sudo dmesg -w | grep EtherCAT > mylog Then Start your node
Hi @ammaraljodah,
They look good to me, from EtherCAT slaves:
0 0:0 PREOP E 0x0000029c:0x02c30001
1 0:1 SAFEOP+ERROR E 0x0000029c:0x02c31001
2 0:2 PREOP + 0x0000029c:0x03b31001
My .yaml:
drive1:
vendor_id: 0x0000029c
product_id: 0x02c30001
drive2:
vendor_id: 0x0000029c
product_id: 0x02c31001
drive3:
vendor_id: 0x0000029c
product_id: 0x03b31001
Here the result of the test: mylog.txt
Best Alessio
Do the debug as in my last post and provide results
You have this showing no default mapping
502.472388] EtherCAT DEBUG 0 0:0: Loading default mapping for PDO 0x1600.
[ 502.472389] EtherCAT DEBUG 0 0:0: No default mapping found.
Other than that the driver was responding to the SDOs, then it timed out when master requests OP mode.
It is driver issue, you need to configure your driver and save the mapping using the software of the driver if there is one. Or, you write the SDOs to map the PDOs.
At this point all Troubleshooting should be on the driver side.
HI @ammaraljodah,
In the driver software seems that it is not possible to map the PDO (I will try to investigate more). Therefore, I think that the only possible solution is to write the SDOs to map the PDOs. Do you know if it is possible with ethercat_driver_ros2? If so, do you have any example ? Or can you explain how to do ? If I add them to config.yaml where also the PDOs are defined ?
Many thanks Best Regards Alessio
Use Twincat to map the PDOs Then copy the startup SDOs that has been generated from the mapping. See this video: https://youtu.be/2R-GD2JqNWI?si=ETbKEnLDkqAYskOJ While you are in Twincat, I recommend you test the drive and enable and move motor to have independent check of your hardware, before coming to this library. In terms of the ros library The SDOs can be sent by adding them in the yaml
See this for how to send SDOs on startup https://github.com/ICube-Robotics/ethercat_driver_ros2_examples
Hi @ammaraljodah,
If I understand correctly, I need to follow these steps
Then copy the startup SDOs that has been generated from the mapping.
how ? Should I use wireshark or somenthing else?
am I missing something?
Best Alessio
In the startup tab in twincat you will see the list of sdo that has been generated from the mapping. Watch the video above at: 6:33
Dear @ammaraljodah,
On Monday when I will be in lab I will try and I will update you here. Many thanks for your time,
Best Alessio
Hi @ammaraljodah, I have followed the video and here is Twincat's sdo:
However, it is unclear to me how I should implement the sdo in the yaml.
I have tried:
sdo:
- {index: 0x1600, sub_index: 0, type: uint32, value: 0x60400010}
- {index: 0x1600, sub_index: 1, type: uint32, value: 0x607A0020}
- {index: 0x1600, sub_index: 2, type: uint32, value: 0x60FF0020}
- {index: 0x1600, sub_index: 3, type: uint32, value: 0x60600008}
- {index: 0x1600, sub_index: 4, type: uint32, value: 0x60710010}
- {index: 0x1a00, sub_index: 0, type: uint32, value: 0x60410010}
- {index: 0x1a00, sub_index: 1, type: uint32, value: 0x60640020}
- {index: 0x1a00, sub_index: 2, type: uint32, value: 0x606C0020}
- {index: 0x1a00, sub_index: 3, type: uint32, value: 0x60610008}
- {index: 0x1a00, sub_index: 4, type: uint32, value: 0x60770010}
- {index: 0x1a00, sub_index: 5, type: uint32, value: 0x603F0010}
- {index: 0x1C12, sub_index: 0, type: uint32, value: 0x1600}
- {index: 0x1C13, sub_index: 0, type: uint32, value: 0x1A00}
and I got:
0 0:0 PREOP E 0x0000029c:0x02c30001
Do you know what I am doing wrong with the sdo? I am not pretty sure about the subindex.
Best Alessio
The mapping seems odd. Try uploading your drive esi file to twincat and see the startup sdos.
Hi =D
I am trying to control three Everest XCR drives using ROS2 EtherCAT driver. I followed the instructions from this guide. However, I can only enable and move one drive (Drive 3), while the others do not reach the "operation enabled" state.
Since my 3 drives have different product IDs, I created separate YAML configuration files for each of them. I also attempted to switch the RPDO and TPDO orders without success. Below are the details of the configuration for each drive.
The drive's reference manual manual EtherCAT & CANopen registers link
Configuration for Drive 1 (EVE XCR):
Configuration for Drive 2 (EVE XCR):
Configuration for Drive 3 (Working drive EVE S XCR):
Below is the ros2_control EtherCAT configuration:
My setup is based on Ubuntu 22.04 and ROS2 Rolling.
I've attached the dmesg output obtained with EtherCAT debug level set to 1 for both scenarios (with and without the 0x6060 register).
the output from ros2 for the first scenario is:
The output from ros2 for second scenario (without x6060) is:
test_with.txt test_without_6060.txt
Many thanks for your time
Best Alessio