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

ethercat master dc synchronization #110

Open hanafym opened 3 months ago

hanafym commented 3 months ago

Hi, I don't know if this is an issue per se, but I have noticed that the following snippet from the function void EcMaster::update(uint32_t domain) in ec_master.cpp

clock_gettime(CLOCK_REALTIME, &t);
ecrt_master_application_time(master_, EC_NEWTIMEVAL2NANO(t));
ecrt_master_sync_reference_clock(master_);
ecrt_master_sync_slave_clocks(master_);

only gets called once, unlike the implementation in the igh example https://gitlab.com/etherlab.org/ethercat/-/blob/master/examples/dc_user/main.c?ref_type=heads where they are called every cycle. Is there a reason why it is implemented this way here. Also how would that affect dc synchronization mode using SYNC0 signal. I expect that the slave clocks would need to be synched every now and then due to the clock drift.

hanafym commented 3 months ago

Nvm i totally missed the implementation in the function EcMaster::writeData(uint32_t domain), however it takes a really long time for synchronization, more than 10 seconds, is this normal?

PieterjanCottignies commented 3 months ago

Hi @hanafym what is your cycle time and how are you checking synchronisation?

I'm also looking into the DC-Sync implementation to hopefully solve some jitter issues. In the EtherCAT master documentation about the DC-Sync I understand the Drift compensation topic to mean that the time controller gradually works out the drift so maybe this can take some time: https://gitlab.com/etherlab.org/ethercat/-/jobs/artifacts/stable-1.5/raw/pdf/ethercat_doc.pdf?job=pdf

hanafym commented 3 months ago

I am using a cycle time of 4 ms, and I am checking synchronization by reading the register 0x92c (which stores the system time difference) from the controller. Yes I couldn't find anything specifying how long synchronization usually takes so I guess the users simply needs to wait for it to be complete.