Hi everyone,
I have gone silent in that topic for much longer than expected due to other
obligations. However, the problem was becoming more and more crucial to solve,
hence I finally managed to find some time for it. I dug in it and eventually
found a fix.
tl;dr version: the EoE thread was responsible for all the mess I experienced.
Recompiling the master with --disable-eoe solved the problem on all affected
machines. Precise cause of the problem remains unknown for me, but I won't
investigate further, since my time is limited. If anyone from the Etherlab
developers wants to investigate this issue, I will be happy to provide any
further info you may need or run whichever test code you may want me to run.
Just let me know.
Full version:
1. First, I made a hello world version of my code (main.cpp attached here)
as suggested. That didn't manage to solve the issue. The problematic behaviour
remained unchanged
2. The thing that helped to some extent was switching from Kernel 4.19 to
4.4. The issue started appearing more seldom, although after some time the
master would unavoidably malfunction. The downside was that it also started to
appear regardless whether the application was run for the first or consecutive
times.
3.
I thought the problem may be due to the fact that I used -lowlatency kernel
instead of RTPREEMPT. I patched and installed 4.4.270-rt222 kernel on Ubuntu
18.04 on one of the affected computers. No change.
4.
At this point I was already planning to write the message to this mailing list
asking for any further suggestions. I was copying the output from dmesg after a
crash. The output looked like this:
[ 213.803906] e1000e: enp3s0f0 NIC Link is Down
[ 217.855649] e1000e: enp3s0f0 NIC Link is Up 100 Mbps Full Duplex, Flow
Control: None
[ 217.855770] e1000e 0000:03:00.0 enp3s0f0: 10/100 speed: disabling TSO
[ 223.034625] EtherCAT: Master driver 1.5.2 365eea9297ef
[ 223.035309] EtherCAT: 1 master waiting for devices.
[ 223.211992] e1000e: enp3s0f1 NIC Link is Down
[ 223.403064] e1000e: enp3s0f0 NIC Link is Down
[ 223.440810] e1000e 0000:00:19.0 eno1: removed PHC
[ 223.561885] e1000e: eno1 NIC Link is Down
[ 223.605592] ec_e1000e: EtherCAT-capable Intel(R) PRO/1000 Network Driver -
3.2.6-k-EtherCAT
[ 223.605597] ec_e1000e: Copyright(c) 1999 - 2015 Intel Corporation.
[ 223.605851] ec_e1000e 0000:00:19.0: Interrupt Throttling Rate (ints/sec) set
to dynamic conservative mode
[ 223.808912] ec_e1000e 0000:00:19.0 eth0: registered PHC clock
[ 223.808919] ec_e1000e 0000:00:19.0 eth0: (PCI Express:2.5GT/s:Width x1)
b8:ca:3a:7a:a4:4b
[ 223.808923] ec_e1000e 0000:00:19.0 eth0: Intel(R) PRO/1000 Network Connection
[ 223.808989] ec_e1000e 0000:00:19.0 eth0: MAC: 10, PHY: 11, PBA No: 1011FF-0FF
[ 223.809238] ec_e1000e 0000:03:00.0: Interrupt Throttling Rate (ints/sec) set
to dynamic conservative mode
[ 223.811898] ec_e1000e 0000:00:19.0 eno1: renamed from eth0
[ 223.828469] IPv6: ADDRCONF(NETDEV_UP): eno1: link is not ready
[ 223.982809] EtherCAT: Accepting 00:24:81:81:A6:98 as main device for master
0.
[ 224.063994] IPv6: ADDRCONF(NETDEV_UP): eno1: link is not ready
[ 224.127583] EtherCAT 0: Starting EtherCAT-IDLE thread.
[ 224.127784] ec_e1000e 0000:03:00.0 ecm0 (uninitialized): (PCI
Express:2.5GT/s:Width x4) 00:24:81:81:a6:98
[ 224.127791] ec_e1000e 0000:03:00.0 ecm0 (uninitialized): Intel(R) PRO/1000
Network Connection
[ 224.127876] ec_e1000e 0000:03:00.0 ecm0 (uninitialized): MAC: 0, PHY: 4, PBA
No: D51930-006
[ 224.128134] ec_e1000e 0000:03:00.1: Interrupt Throttling Rate (ints/sec) set
to dynamic conservative mode
[ 224.302086] ec_e1000e 0000:03:00.1 eth0: (PCI Express:2.5GT/s:Width x4)
00:24:81:81:a6:99
[ 224.302093] ec_e1000e 0000:03:00.1 eth0: Intel(R) PRO/1000 Network Connection
[ 224.302176] ec_e1000e 0000:03:00.1 eth0: MAC: 0, PHY: 4, PBA No: D51930-006
[ 224.309653] ec_e1000e 0000:03:00.1 enp3s0f1: renamed from eth0
[ 224.338049] IPv6: ADDRCONF(NETDEV_UP): enp3s0f1: link is not ready
[ 224.582923] IPv6: ADDRCONF(NETDEV_UP): enp3s0f1: link is not ready
[ 225.430594] EtherCAT: Requesting master 0...
[ 225.430602] EtherCAT: Successfully requested master 0.
[ 225.430682] EtherCAT 0: Domain0: Logical address 0x00000000, 15 byte,
expected working counter 3.
[ 225.430686] EtherCAT 0: Datagram domain0-0-main: Logical offset
0x00000000, 15 byte, type LRW at ffff8807efdb9d98.
[ 225.430705] EtherCAT 0: Master thread exited.
[ 225.430708] EtherCAT 0: Starting EtherCAT-OP thread.
[ 226.128409] ec_e1000e: ecm0 NIC Link is Up 100 Mbps Full Duplex, Flow
Control: None
[ 226.128533] ec_e1000e 0000:03:00.0 ecm0 (uninitialized): 10/100 speed:
disabling TSO
[ 226.128538] EtherCAT 0: Link state of ecm0 changed to UP.
[ 226.130421] EtherCAT 0: 4 slave(s) responding on main device.
[ 226.130427] EtherCAT 0: Slave states on main device: INIT.
[ 226.136394] EtherCAT 0: Scanning bus.
[ 227.306357] EtherCAT 0: eoe0s2 MAC address derived from NIC part of ecm0 MAC
address
[ 227.306529] EtherCAT 0-main-2: Linked to EoE handler eoe0s2
[ 227.314849] IPv6: ADDRCONF(NETDEV_UP): eoe0s2: link is not ready
[ 227.345422] ec_e1000e: eno1 NIC Link is Up 1000 Mbps Full Duplex, Flow
Control: None
[ 227.345462] IPv6: ADDRCONF(NETDEV_CHANGE): eno1: link becomes ready
[ 227.406341] EtherCAT 0: eoe0s0 MAC address derived from NIC part of ecm0 MAC
address
[ 227.406507] EtherCAT 0-main-0: Linked to EoE handler eoe0s0
[ 227.406514] EtherCAT 0: eoe0s1 MAC address derived from NIC part of ecm0 MAC
address
[ 227.406614] EtherCAT 0-main-1: Linked to EoE handler eoe0s1
[ 227.427331] EtherCAT 0: Bus scanning completed in 1297 ms.
[ 227.427335] EtherCAT 0: Using slave main-0 as DC reference clock.
[ 227.427338] EtherCAT 0: Starting EoE thread.
[ 227.427391] EtherCAT WARNING 0: No app_time received up to now, abort DC
time offset calculation.
[ 227.428355] EtherCAT 0: Slave states on main device: PREOP.
[ 227.428670] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
[ 227.432557] IPv6: ADDRCONF(NETDEV_UP): eoe0s1: link is not ready
[ 227.434341] EtherCAT 0: Slave states on main device: INIT, PREOP.
[ 227.449362] EtherCAT 0: Slave states on main device: PREOP.
[ 227.553348] EtherCAT 0: Domain 0: Working counter changed to 2/3.
[ 227.554351] EtherCAT 0: Slave states on main device: PREOP, SAFEOP.
[ 227.562356] EtherCAT 0: Slave states on main device: PREOP, OP.
[ 227.662329] EtherCAT WARNING 0-main-2: Failed to receive mbox check datagram
for eoe0s2.
[ 227.662334] EtherCAT WARNING 0-main-0: Failed to receive mbox check datagram
for eoe0s0.
[ 227.662336] EtherCAT WARNING 0-main-1: Failed to receive mbox check datagram
for eoe0s1.
(here comes more of similar messages every few seconds, until the moment of
crash:)
[ 471.071642] EtherCAT WARNING 0-main-2: No sending response for eoe0s2 after
100 tries.
[ 475.148519] EtherCAT 0: Domain 0: Working counter changed to 0/12.
[ 475.463475] EtherCAT WARNING 0: 1 datagram UNMATCHED!
[ 475.491858] EtherCAT WARNING: Datagram ffff8807f58aab58 (domain0-0-main) was
SKIPPED 1 time.
[ 475.540531] EtherCAT WARNING 0-main-1: Failed to receive mbox check datagram
for eoe0s1.
[ 476.149554] EtherCAT 0: Domain 0: Working counter changed to 12/12.
(at this point the master freezes; the slaves go into "EtherCAT communication
error" mode and start blinking with red lights like a christmas tree. The
master is locked and I need to reset the computer and slaves to bring the
situation back to normal)
Fortunately, I got sidetracked while copying this output. I closed the terminal
and did something else for like 3 minutes. When I came back to the issue and
ran dmesg again, I was shocked to see some extra info:
[ 600.784147] INFO: task EtherCAT-EoE:4601 blocked for more than 120 seconds.
[ 600.784153] Tainted: G OE 4.4.0-270-rt222 #2
[ 600.784154] "echo 0 > /proc/sys/kernel/hung_task_timeout_secs" disables this
message.
[ 600.784156] EtherCAT-EoE D ffff8807f21ffd40 0 4601 2 0x00000000
[ 600.784160] ffff8807f21ffd40 ffff8807f7a28f80 ffff8807f4a45d00
ffff8807f2200000
[ 600.784163] ffff8807f4a45d00 ffff8807f4a45d00 7fffffffffffffff
ffff8807f679db48
[ 600.784166] ffff8807f21ffd60 ffffffff8185551b 7fffffffffffffff
ffff8807f679c080
[ 600.784169] Call Trace:
[ 600.784176] [<ffffffff8185551b>] schedule+0x4b/0xe0
[ 600.784178] [<ffffffff81857f90>] schedule_timeout+0x1c0/0x2f0
[ 600.784188] [<ffffffffc06cc6db>] ? e1000_intr_msi+0x6b/0x210 [ec_e1000e]
[ 600.784191] [<ffffffff81856af6>] __down+0x76/0xc0
[ 600.784194] [<ffffffff810b0700>] ? __sched_fork+0x1f0/0x230
[ 600.784197] [<ffffffff810d8541>] down+0x41/0x50
[ 600.784208] [<ffffffffc063b886>] ec_master_eoe_thread+0xb6/0x210 [ec_master]
[ 600.784216] [<ffffffffc063b7d0>] ? ecrt_master_reset+0x40/0x40 [ec_master]
[ 600.784218] [<ffffffff810aac87>] kthread+0xe7/0x100
[ 600.784221] [<ffffffff810aaba0>] ? kthread_worker_fn+0x170/0x170
[ 600.784224] [<ffffffff81859ac5>] ret_from_fork+0x55/0x80
[ 600.784226] [<ffffffff810aaba0>] ? kthread_worker_fn+0x170/0x170
Bingo!!!
5. I reset the computer. Purged the master and reinstalled it ffrom source with
the "--disable-eoe" command during configuration. The problem has vanished
entirely.
6. I tested the fix on all affected machines (3 in total) on kernels 4.4-rt,
4.4-lowlatency, and 4.19-lowlatency. It was definitely EoE. Since I don't
really need this protocol and don't know much about it, I didn't investigate
any further.
Personally, at this point I am happy to have a functioning EtherCAT stack and I
don't need to know, why I experienced this issue. Perhaps it is known to the
dev team. However, if that's not the case and any Etherlab developer wanted to
track it further, I can provide all the assistance required. If you need me to
collect any info for you or run any test application, just reach out and I will
be happy to help.
Once again thank you very much for this amazing piece of software and your
assistance with my problem.
Best regards,
Dr. Jakub Sikorski
Surgical Robotics Laboratory
Horstring W-130
University of Twente
Drienerlolaan 5
7500AE Enschede
The Netherlands
[email protected]
________________________________
From: Sikorski, J. (ET)
Sent: 03 March 2021 00:30:55
To: Richard Hacker; [email protected]
Subject: Re: [Etherlab-users] Fw: Master malfunctions after a few runs of a
program
Hi Richard,
This is actually a stunningly obvious and powerful suggestion that I completely
overlooked. Thank you a lot.
I will do exactly that. Should post again within this thread once I get down to
it. May take a week or two, as this is not the only project I'm handling atm.
And honestly, after dealing with the master for years now, I rather expect my
code or the hardware (slaves or the network card) to be the source of the
problem.
But I will see after I get the "hello world" running.
Best,
Jakub
________________________________
From: Richard Hacker <[email protected]>
Sent: 03 March 2021 00:15:55
To: [email protected]
Cc: Sikorski, J. (ET)
Subject: Re: [Etherlab-users] Fw: Master malfunctions after a few runs of a
program
Hi Jakub,
You seem to be using an application with quite a distributed and
sophisticated functionality -- sorry if I'm treading on your feet there!
This is certainly necessary when you want to reuse code the way you are
doing, but to debug it when things don't work out becomes increasingly
more difficult. On an philosophical note: nothing is for free ;)
You say it had been working in a number of previous applications.
Unfortunately even that may go wrong. As Einstein once said:
No number of experiments can prove my theory right, but it takes only
one to prove it wrong!
What it boils down to is: you will have to reduce your code to a
straight forward, no frills and dingbats, three liner straight forward
C-type hello world:
1) get resources
2) configure
3) activate
4) run in cyclic mode
in the sense of the provided examples (ok that was four lines ;) )
I am not postulating that the master is exempt from bugs even though it
is running on thousands of applications (see above), but when you're
juggling with C-type pointers you can get silent corruption in places
that you never expected. The fact that the master hangs is certainly not
right, but you'll only find it when one side (your application) is
completely predictable.
On a side note: recently I was involved in slave development. My master
was also coughing and I thought it was due to my code on the slave. It
boiled down to my network adapter (Intel I219-V) on the master trying to
be clever by bundling frames together before passing them to the kernel
(aka master). A disaster for real time applications! But my three-liner
helped reducing the possible failure space.
Happy coding!
Richard
On 2021-03-01 21:38, [email protected] wrote:
> (apologies if it happens to get posted it multiple times, an earlier
> version of this message was seemingly cancelled by me while waiting for
> moderation)
>
> Hi everyone,
>
>
> For a few years now I have been using the Etherlab master stack with
> Gavin Lambert's patchset to drive embedded systems for my research. It's
> an amazing piece of software and I am truly impressed by this work. For
> my applications I have a thin C++ wrapper that allows me to manage the
> ECRT code through classes and reuse it depending on the project. I coded
> the wrapper myself. I'm not fully sure if it is correct, but it has been
> working fine so far...
>
>
> However, recently, I have installed the stack on a new computer with
> Ubuntu 18.04, Kernel 4.19.177-0419177-lowlatency. I applied all the
> patches from GL and use ec_e1000e driver with a supposedly compatible
> Intel Card (Model EXPI9402PT). I use the stack to drive Technosoft
> Motion iPos4808 BX-CAT drives.
>
>
> Once I run my code *for the first time*, everything seems to work fine
> until the application exits. Then one of three things can happen:
>
>
> Either:
>
> 1. I can run the application again from start to the end, no issue.
> 2. The application stops working during either
> ecrt_master_activate(master) or ecrt_request_master(0). Neither of
> these functions returns and the code just hangs there.
> 3. The communication works fine for some time, then starts acting up.
> It stops working entirely during the operation (suddenly the data
> I'm receiving ends up corrupted) or while exiting (the code hangs, I
> think also on ecrt_master_deactivate(master) or ecrt_release_master(0)).
>
>
> When the application malfunctions, I can only force quit it. If I do, I
> have to reboot the computer, as, whatever ethercat-related I do next, I
> receive the error that the module ec_e1000 is still in use.
>
> Dmesg from a normal run:
>
> [ 1166.127739] EtherCAT: Requesting master 0...
> [ 1166.127743] EtherCAT: Successfully requested master 0.
> [ 1166.127980] EtherCAT 0: Domain0: Logical address 0x00000000, 21 byte,
> expected working counter 3.
> [ 1166.127982] EtherCAT 0: Datagram domain0-0-main: Logical offset
> 0x00000000, 21 byte, type LRW at 0000000098dbfebf.
> [ 1166.128029] EtherCAT 0: Master thread exited.
> [ 1166.128030] EtherCAT 0: Stopping EoE thread.
> [ 1166.128052] EtherCAT 0: EoE thread exited.
> [ 1166.128053] EtherCAT 0: Starting EoE thread.
> [ 1166.128382] EtherCAT 0: Starting EtherCAT-OP thread.
> [ 1166.131218] EtherCAT WARNING 0: No app_time received up to now, abort
> DC time offset calculation.
> [ 1166.176215] EtherCAT 0: Slave states on main device: INIT.
> [ 1166.200217] EtherCAT 0: Slave states on main device: PREOP.
> [ 1166.443626] EtherCAT 0: Domain 0: Working counter changed to 2/3.
> [ 1166.456205] EtherCAT 0: Slave states on main device: SAFEOP.
> [ 1166.464205] EtherCAT 0: Slave states on main device: OP.
> [ 1167.128196] EtherCAT WARNING 0: 2 datagrams UNMATCHED!
> [ 1167.131459] EtherCAT WARNING: Datagram 0000000098dbfebf
> (domain0-0-main) was SKIPPED 2 times.
> [ 1167.447503] EtherCAT 0: Domain 0: 3 working counter changes - now 3/3.
> [ 1170.264093] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> (This continues until the end)
> [ 1193.785359] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 1193.894348] EtherCAT 0: Slave states on main device: SAFEOP + ERROR.
> [ 1194.793518] EtherCAT 0: Master thread exited.
> [ 1194.793520] EtherCAT 0: Stopping EoE thread.
> [ 1194.793538] EtherCAT 0: EoE thread exited.
> [ 1194.793547] EtherCAT 0: Starting EoE thread.
> [ 1194.793674] EtherCAT 0: Starting EtherCAT-IDLE thread.
> [ 1194.793856] EtherCAT 0: 0 slave(s) responding on main device.
> [ 1194.795324] EtherCAT ERROR 0-main-0: AL status message 0x001B: "Sync
> manager watchdog".
> [ 1194.797319] EtherCAT 0: 1 slave(s) responding on main device.
> [ 1194.797321] EtherCAT 0: Slave states on main device: SAFEOP + ERROR.
> [ 1194.799335] EtherCAT 0-main-0: Acknowledged state SAFEOP.
> [ 1194.801321] EtherCAT 0: Slave states on main device: SAFEOP.
> [ 1194.805320] EtherCAT 0: Slave states on main device: INIT.
> [ 1194.817333] EtherCAT 0: Slave states on main device: PREOP.
> [ 1195.281308] EtherCAT WARNING: Datagram 00000000f3c9ebae (master-fsm)
> was SKIPPED 1 time.
> [ 1195.793926] EtherCAT 0: Releasing master...
> [ 1195.793929] EtherCAT 0: Released.
> [ 1195.797305] EtherCAT 0: Stopping EoE thread.
> [ 1195.797324] EtherCAT 0: EoE thread exited.
> [ 1195.810428] EtherCAT 0: Scanning bus.
> [ 1196.038438] EtherCAT 0: eoe0s0 MAC address derived from NIC part of
> ecm0 MAC address
> [ 1196.038615] EtherCAT 0-main-0: Linked to EoE handler eoe0s0
> [ 1196.038620] EtherCAT 0: Bus scanning completed in 241 ms.
> [ 1196.038622] EtherCAT 0: Using slave main-0 as DC reference clock.
> [ 1196.038623] EtherCAT 0: Starting EoE thread.
> [ 1196.049270] EtherCAT 0: Slave states on main device: INIT.
> [ 1196.050455] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
> [ 1196.061266] EtherCAT 0: Slave states on main device: PREOP.
>
> Dmesg from a "normal" run that precedes to crash:
>
> [ 3289.782513] EtherCAT: Requesting master 0...
> [ 3289.969220] EtherCAT 0: eoe0s0 MAC address derived from NIC part of
> ecm0 MAC address
> [ 3289.970078] EtherCAT 0-main-0: Linked to EoE handler eoe0s0
> [ 3289.970087] EtherCAT 0: Bus scanning completed in 229 ms.
> [ 3289.970089] EtherCAT 0: Using slave main-0 as DC reference clock.
> [ 3289.970091] EtherCAT 0: Starting EoE thread.
> [ 3289.970100] EtherCAT: Successfully requested master 0.
> [ 3289.970321] EtherCAT 0: Domain0: Logical address 0x00000000, 21 byte,
> expected working counter 3.
> [ 3289.970323] EtherCAT 0: Datagram domain0-0-main: Logical offset
> 0x00000000, 21 byte, type LRW at 00000000e95eb248.
> [ 3289.970341] EtherCAT 0: Master thread exited.
> [ 3289.970342] EtherCAT 0: Stopping EoE thread.
> [ 3289.970349] EtherCAT 0: EoE thread exited.
> [ 3289.970350] EtherCAT 0: Starting EoE thread.
> [ 3289.970386] EtherCAT 0: Starting EtherCAT-OP thread.
> [ 3289.977769] EtherCAT WARNING 0: No app_time received up to now, abort
> DC time offset calculation.
> [ 3289.985470] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
> [ 3289.985571] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
> [ 3289.991646] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
> [ 3289.995472] IPv6: ADDRCONF(NETDEV_UP): eoe0s0: link is not ready
> [ 3290.019763] EtherCAT 0: Slave states on main device: INIT.
> [ 3290.043756] EtherCAT 0: Slave states on main device: PREOP.
> [ 3290.270841] EtherCAT 0: Domain 0: Working counter changed to 3/3.
> [ 3290.279764] EtherCAT 0: Slave states on main device: SAFEOP.
> [ 3290.287760] EtherCAT 0: Slave states on main device: OP.
> [ 3290.651875] ec_e1000e: eno1 NIC Link is Up 1000 Mbps Full Duplex,
> Flow Control: None
> [ 3290.651920] IPv6: ADDRCONF(NETDEV_CHANGE): eno1: link becomes ready
> [ 3290.969766] EtherCAT WARNING 0: 5 datagrams UNMATCHED!
> [ 3290.974674] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 5 times.
> [ 3290.976777] IPv6: ADDRCONF(NETDEV_CHANGE): eoe0s0: link becomes ready
> [ 3291.274830] EtherCAT 0: Domain 0: 12 working counter changes - now 3/3.
> [ 3291.972739] EtherCAT WARNING 0: 5 datagrams UNMATCHED!
> [ 3291.974880] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 5 times.
> [ 3292.094807] EtherCAT WARNING 0-main-0: No sending response for eoe0s0
> after 100 tries.
> [ 3292.278983] EtherCAT 0: Domain 0: 2 working counter changes - now 3/3.
> [ 3292.990788] EtherCAT WARNING 0-main-0: No sending response for eoe0s0
> after 100 tries.
> [ 3294.103893] EtherCAT WARNING 0-main-0: No sending response for eoe0s0
> after 100 tries.
> [ 3294.887689] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3294.973683] EtherCAT WARNING 0: 2 datagrams UNMATCHED!
> [ 3294.984490] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 2 times.
> [ 3295.891819] EtherCAT 0: Domain 0: 15 working counter changes - now 3/3.
> [ 3295.973667] EtherCAT WARNING 0: 5 datagrams UNMATCHED!
> [ 3295.987844] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 5 times.
> [ 3298.943805] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3299.944793] EtherCAT 0: Domain 0: 13 working counter changes - now 3/3.
> [ 3299.976592] EtherCAT WARNING 0: 6 datagrams UNMATCHED!
> [ 3300.000785] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 6 times.
> [ 3300.538790] EtherCAT WARNING 0-main-0: No sending response for eoe0s0
> after 100 tries.
> [ 3303.009524] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3303.980507] EtherCAT WARNING 0: 9 datagrams UNMATCHED!
> [ 3304.013729] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 9 times.
> [ 3304.013732] EtherCAT 0: Domain 0: 17 working counter changes - now 3/3.
> [ 3304.981498] EtherCAT WARNING 0: 1 datagram UNMATCHED!
> [ 3305.017954] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 1 time.
> [ 3305.017956] EtherCAT 0: Domain 0: 2 working counter changes - now 3/3.
> [ 3306.726450] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3306.981453] EtherCAT WARNING 0: 6 datagrams UNMATCHED!
> [ 3307.022444] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 7 times.
> [ 3307.730694] EtherCAT 0: Domain 0: 19 working counter changes - now 3/3.
> [ 3307.982442] EtherCAT WARNING 0: 4 datagrams UNMATCHED!
> [ 3308.026763] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 3 times.
> [ 3310.479387] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3310.983378] EtherCAT WARNING 0: 5 datagrams UNMATCHED!
> [ 3311.035400] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 5 times.
> [ 3311.141385] EtherCAT WARNING 0-main-0: Failed to receive mbox check
> datagram for eoe0s0.
> [ 3311.274500] EtherCAT WARNING 0-main-0: No sending response for eoe0s0
> after 100 tries.
> [ 3311.483392] EtherCAT 0: Domain 0: 11 working counter changes - now 3/3.
> [ 3314.532303] EtherCAT 0: Domain 0: Working counter changed to 0/3.
> [ 3314.986298] EtherCAT WARNING 0: 3 datagrams UNMATCHED!
> [ 3315.048313] EtherCAT WARNING: Datagram 00000000e95eb248
> (domain0-0-main) was SKIPPED 5 times.
> [ 3315.536416] EtherCAT 0: Domain 0: 13 working counter changes - now 3/3.
> [ 3315.989282] EtherCAT WARNING 0: 2 datagrams UNMATCHED!
> [ 3317.715249] EtherCAT 0: Slave states on main device: SAFEOP + ERROR.
> [ 3318.613273] EtherCAT 0: Master thread exited.
> [ 3318.613275] EtherCAT 0: Stopping EoE thread.
> [ 3318.613343] EtherCAT 0: EoE thread exited.
> [ 3318.613353] EtherCAT 0: Starting EoE thread.
> [ 3318.613500] EtherCAT 0: Starting EtherCAT-IDLE thread.
> [ 3318.613614] EtherCAT 0: 0 slave(s) responding on main device.
> [ 3318.616245] EtherCAT ERROR 0-main-0: AL status message 0x001B: "Sync
> manager watchdog".
> [ 3318.618242] EtherCAT 0: 1 slave(s) responding on main device.
> [ 3318.618245] EtherCAT 0: Slave states on main device: SAFEOP + ERROR.
> [ 3318.620256] EtherCAT 0-main-0: Acknowledged state SAFEOP.
> [ 3318.622244] EtherCAT 0: Slave states on main device: SAFEOP.
> [ 3318.627235] EtherCAT 0: Slave states on main device: INIT.
> [ 3318.639238] EtherCAT 0: Slave states on main device: PREOP.
> [ 3318.783218] EtherCAT WARNING: Datagram 0000000019626fd7 (master-fsm)
> was SKIPPED 1 time.
> [ 3319.613733] EtherCAT 0: Releasing master...
> [ 3319.613737] EtherCAT 0: Released.
> [ 3319.615206] EtherCAT 0: Stopping EoE thread.
> (Here Dmesg stream breaks, so maybe it's something related to the EoE
> thread?)
>
>
> Dmesg of a run that hangs forever:
> [ 3363.180585] EtherCAT: Requesting master 0...
> [ 3365.930011] EtherCAT 0: Waiting for slave scan interrupted by signal.
> [ 3365.930023] EtherCAT ERROR 0: Failed to enter OPERATION phase!
> [ 3370.924180] ec_e1000e: enp3s0f1 NIC Link is Down
> [ 3370.942351] EtherCAT 0: Stopping EoE thread.
> (Again, the last command is "Stopping EoE thread", but the application
> hangs forever at that point.)
>
>
> The way I start and end the Ethercat master operation is equivalent to
> what I found in the examples, but I distributed and encapsulated it in a
> few classes for reuse.
> The code I use to initialize the master:
>
> int EthercatBus::begin_operation()
> {
> if(!network_operating)
> {
> //ECRT Related
>
> if(sc.size())
> {
> mass_configure_DOs(); // This function configures SDOs/PDOs
> }
> ecrt_master_activate(master);
> datagram_begin = ecrt_domain_data(domain1);
>
> //Initialize the EtherCAT thread
>
>
> ethercat_thread=make_shared<boost::thread>(&EthercatBus::function_ethercat_thread,this);
> //Cyclic task starts here
> network_operating = 1;
> cout << "Ethercat Network Operational"<< endl;
>
>
> if(!slaves_configured && sc.size())
> {
> switch_on_slaves(); //This function pushes each slave through
> slave-specific initialization using PDOs + Controlword
> slaves_configured = 1;
> }
> else if(!sc.size())
> {
> slaves_configured = 1;
> }
> }
>
> cout << "Slaves On"<< endl;
> }
>
>
>
> The code which I use to deinitialize and release the master is here:
>
> int EthercatBus::end_operation()
> {
> if(network_operating)
> {
>
> cout << "Shutting down network" << endl;
>
> for (vector<shared_ptr<EthercatSlave>>::iterator
> iter=sc.begin(); iter != sc.end(); iter++)
> {
>
> int locA = (*iter)->alias;
> int locPos = (*iter)->position;
> cout << "Shutting down slave : " << locA << "/" << locPos
> << endl;
>
> (*iter)->switch_off(); //Slave specific deinitialization
> procedure. Cyclic tasks still run at this point.
>
> cout << "Slave : " << locA << "/" << locPos << " Shut Down"
> << endl;
> }
>
> usleep (1e6);
>
>
> ethercat_thread->interrupt(); // Cyclic task stopped
> ethercat_thread->join();
> ethercat_thread.reset();
>
> usleep (1e6);
>
>
> cout << "Thread Returned" << endl;
> ecrt_master_deactivate(master);
> cout << "EthercatBus - Master Deactivated" << endl;
> usleep (1e6);
> ecrt_release_master(master);
>
>
> cout << "EthercatBus - Master Released" << endl;
>
> for (vector<shared_ptr<EthercatSlave>>::iterator
> iter=sc.begin(); iter != sc.end();)
> {
> sc.erase(iter);
> }
>
> cout << "Ethercat Network shut down" << endl;
> network_operating=0;
> }
> }
>
> The most non-standard thing in my code, which may be the source of an
> error, is definitely the use of a PI controller for timing inside a
> cyclic task:
>
> while(!boost::this_thread::interruption_requested()) //Cycle until
> the thread is interrupted.
> {
>
> cycle_frames_receive();
>
> t2=t1; //Store the beginning time of the previous iteration.
> t1 = high_resolution_clock::now();
> tdiff=duration_cast<microseconds>(t1-t2).count();
>
> local_counter++;
>
> if(local_counter==frequency) //Once every second
> {
>
> local_counter=0;
> }
>
>
> cycle_frames_send();
>
> //PI control over the frame period. Robust up to 10 [kHz]
>
> t_error_P=(1e6/frequency - tdiff); // Proportional Error
> t_error_I= t_error_I + t_error_P; //Integral Error
> msec = msec + gain_P*(t_error_P) + gain_I*t_error_I //;
> Closing the control;
>
> if(first_iter)
> {
> msec=1e6/frequency;
> first_iter=false;
> }
>
> if (msec>0){usleep(msec);} //Saturation, as you cannot wait
> less than 0 microseconds.
>
> }
>
> instead of a regular timer, but this way has always provided me with a
> more exact and stable performance.
>
> *If full source code is required, I can supply it. *
> *
> *
> The entire stack so far worked on 5+ different computers. Similar issues
> _were_ happening in the past sometimes, but like once every 1000 runs
> and always while exiting the application (especially in a forceful
> manner, never during the cyclic communication). On this particular
> machine the master usually gets messed up after 2/3 runs.
>
> Besides iPOS drives, I work also with Copley Controls Xenus drives. I
> have never had any issues with those. Applications with them run
> smoothly (so maybe it's the problem with Technosof slaves?).
> *
> *
> *I thought it is a problem of the ec_e1000e driver, but the issue
> persists when I use ec_generic driver. *
>
> Has anyone ever encountered a similar problem? I have zero knowledge of
> how the ecrt stack is coded internally. If anyone could tell me what I
> am doing wrong, or at least point me towards any way, in which I could
> establish that, I would be extremely obliged.
>
> Yours faithfully,
> Dr. Jakub Sikorski
>
> Surgical Robotics Laboratory
> Horstring W-130
> University of Twente
> 7500AE Enschede
> The Netherlands
> [email protected]
>
>
>
>
>
>
>
>
Mit freundlichem Gruß
Richard Hacker
--
------------------------------------------------------------------------
Richard Hacker M.Sc.
[email protected]
Tel.: +49 201 / 36014-16
Ingenieurgemeinschaft IgH
Gesellschaft für Ingenieurleistungen mbH
Nordsternstraße 66
D-45329 Essen
Amtsgericht Essen HRB 11500
USt-Id.-Nr.: DE 174 626 722
Geschäftsführung:
- Dr.-Ing. Siegfried Rotthäuser
- Dr. Sven Beermann, Prokurist
Tel.: +49 201 / 360-14-0
http://www.igh.de
------------------------------------------------------------------------
/*****************************************************************************
*
* $Id$
*
* Copyright (C) 2007-2009 Florian Pose, Ingenieurgemeinschaft IgH
*
* This file is part of the IgH EtherCAT Master.
*
* The IgH EtherCAT Master is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License version 2, as
* published by the Free Software Foundation.
*
* The IgH EtherCAT Master is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with the IgH EtherCAT Master; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* ---
*
* The license mentioned above concerns the source code only. Using the
* EtherCAT technology and brand is only permitted in compliance with the
* industrial property and similar rights of Beckhoff Automation GmbH.
*
****************************************************************************/
#include <errno.h>
#include <signal.h>
#include <iostream>
#include <stdio.h>
#include <string.h>
#include <sys/resource.h>
#include <sys/time.h>
#include <sys/types.h>
#include <unistd.h>
#include <time.h> /* clock_gettime() */
#include <sys/mman.h> /* mlockall() */
#include <sched.h> /* sched_setscheduler() */
/****************************************************************************/
#include "ecrt.h"
/****************************************************************************/
/** Task period in ns. */
#define PERIOD_NS (1000000)
#define MAX_SAFE_STACK (8 * 1024) /* The maximum stack size which is
guranteed safe to access without
faulting */
/****************************************************************************/
/* Constants */
#define NSEC_PER_SEC (1000000000)
#define FREQUENCY (NSEC_PER_SEC / PERIOD_NS)
/****************************************************************************/
// EtherCAT
static ec_master_t *master = NULL;
static ec_master_state_t master_state = {};
static ec_domain_t *domain1 = NULL;
static ec_domain_state_t domain1_state = {};
static ec_slave_config_t *sc_ipos = NULL;
static ec_slave_config_state_t sc_ipos_state = {};
/****************************************************************************/
// process data
static uint8_t *domain1_pd = NULL;
#define DrivePos 0, 0
#define Technosoft_iPOS3602VXCAT 0x000001a3,0x01ab46e5
// offsets for PDO entries
static unsigned int off_1;
static unsigned int off_2;
static unsigned int off_3;
static unsigned int off_4;
static unsigned int off_5;
static unsigned int off_6;
static unsigned int off_7;
const static ec_pdo_entry_reg_t domain1_regs[] = {
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6040, 0x00, &off_1},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6060, 0x00, &off_2},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6086, 0x00, &off_3},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6071, 0x00, &off_4},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6041, 0x00, &off_5},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6077, 0x00, &off_6},
{DrivePos, Technosoft_iPOS3602VXCAT, 0x6064, 0x00, &off_7},
{}
};
static unsigned int counter = 0;
static unsigned int blink = 0;
/*****************************************************************************/
// IPOS 3602 --------------------------
static ec_pdo_entry_info_t i3602_pdo_entries[] = {
{0x6040, 0, 16}, // channel 1 status
{0x6060, 0, 8}, // channel 1 value
{0x6086, 0, 16}, // channel 2 status
{0x6071, 0, 16}, // channel 2 value
{0x6041, 0, 16}, // channel 1 value (alt.)
{0x6077, 0, 16}, // channel 2 value (alt.)
{0x6064, 0, 32}, // channel 2 value
};
static ec_pdo_info_t i3602_rx_pdos[] = {
{0x1600, 3, i3602_pdo_entries},
{0x1601, 1, i3602_pdo_entries + 3}
};
static ec_pdo_info_t i3602_tx_pdos[] = {
{0x1A00, 3, i3602_pdo_entries+4}
};
static ec_sync_info_t i3602_syncs[] = {
{2, EC_DIR_OUTPUT, 2, i3602_rx_pdos, EC_WD_DEFAULT},
{3, EC_DIR_INPUT, 1, i3602_tx_pdos, EC_WD_DEFAULT},
{0xff}
};
/*****************************************************************************/
void check_domain1_state(void)
{
ec_domain_state_t ds;
ecrt_domain_state(domain1, &ds);
if (ds.working_counter != domain1_state.working_counter) {
printf("Domain1: WC %u.\n", ds.working_counter);
}
if (ds.wc_state != domain1_state.wc_state) {
printf("Domain1: State %u.\n", ds.wc_state);
}
domain1_state = ds;
}
/*****************************************************************************/
void check_master_state(void)
{
ec_master_state_t ms;
ecrt_master_state(master, &ms);
if (ms.slaves_responding != master_state.slaves_responding) {
printf("%u slave(s).\n", ms.slaves_responding);
}
if (ms.al_states != master_state.al_states) {
printf("AL states: 0x%02X.\n", ms.al_states);
}
if (ms.link_up != master_state.link_up) {
printf("Link is %s.\n", ms.link_up ? "up" : "down");
}
master_state = ms;
}
/*****************************************************************************/
void check_slave_config_states(void)
{
ec_slave_config_state_t s;
ecrt_slave_config_state(sc_ipos, &s);
if (s.al_state != sc_ipos_state.al_state) {
printf("AnaIn: State 0x%02X.\n", s.al_state);
}
if (s.online !=sc_ipos_state.online) {
printf("AnaIn: %s.\n", s.online ? "online" : "offline");
}
if (s.operational != sc_ipos_state.operational) {
printf("AnaIn: %soperational.\n", s.operational ? "" : "Not ");
}
sc_ipos_state = s;
}
/*****************************************************************************/
void cyclic_task()
{
// receive process data
ecrt_master_receive(master);
ecrt_domain_process(domain1);
// check process data state
check_domain1_state();
if (counter) {
counter--;
} else { // do this at 1 Hz
counter = FREQUENCY;
// calculate new process data
blink = !blink;
// check for master state (optional)
check_master_state();
// check for slave configuration state(s) (optional)
check_slave_config_states();
std::cout << "Comm Debug" << std::endl;
}
// send process data
ecrt_domain_queue(domain1);
ecrt_master_send(master);
}
/****************************************************************************/
void stack_prefault(void)
{
unsigned char dummy[MAX_SAFE_STACK];
memset(dummy, 0, MAX_SAFE_STACK);
}
/****************************************************************************/
int main(int argc, char **argv)
{
std::cout << "Debug 1 " << std::endl;
ec_slave_config_t *sc;
struct timespec wakeup_time;
int ret = 0;
master = ecrt_request_master(0);
if (!master) {
return -1;
}
domain1 = ecrt_master_create_domain(master);
if (!domain1) {
return -1;
}
std::cout << "Debug 2 " << std::endl;
if (!(sc = ecrt_master_slave_config(
master, DrivePos, Technosoft_iPOS3602VXCAT))) {
fprintf(stderr, "Failed to get slave configuration.\n");
return -1;
}
if (ecrt_slave_config_pdos(sc, EC_END, i3602_syncs)) {
fprintf(stderr, "Failed to configure PDOs.\n");
return -1;
}
sc_ipos=sc;
if (ecrt_domain_reg_pdo_entry_list(domain1, domain1_regs)) {
fprintf(stderr, "PDO entry registration failed!\n");
return -1;
}
std::cout << "Debug 3 " << std::endl;
printf("Activating master...\n");
if (ecrt_master_activate(master)) {
return -1;
}
if (!(domain1_pd = ecrt_domain_data(domain1))) {
return -1;
}
std::cout << "Debug 4 " << std::endl;
/* Set priority */
struct sched_param param = {};
param.sched_priority = sched_get_priority_max(SCHED_FIFO);
printf("Using priority %i.", param.sched_priority);
if (sched_setscheduler(0, SCHED_FIFO, ¶m) == -1) {
perror("sched_setscheduler failed");
}
std::cout << "Debug 5 " << std::endl;
/* Lock memory */
if (mlockall(MCL_CURRENT | MCL_FUTURE) == -1) {
fprintf(stderr, "Warning: Failed to lock memory: %s\n",
strerror(errno));
}
stack_prefault();
printf("Starting RT task with dt=%u ns.\n", PERIOD_NS);
std::cout << "Debug 6 " << std::endl;
clock_gettime(CLOCK_MONOTONIC, &wakeup_time);
wakeup_time.tv_sec += 1; /* start in future */
wakeup_time.tv_nsec = 0;
std::cout << "Debug 7 " << std::endl;
while (1) {
ret = clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME,
&wakeup_time, NULL);
if (ret) {
fprintf(stderr, "clock_nanosleep(): %s\n", strerror(ret));
break;
}
cyclic_task();
wakeup_time.tv_nsec += PERIOD_NS;
while (wakeup_time.tv_nsec >= NSEC_PER_SEC) {
wakeup_time.tv_nsec -= NSEC_PER_SEC;
wakeup_time.tv_sec++;
}
}
return ret;
}
--
Etherlab-users mailing list
[email protected]
https://lists.etherlab.org/mailman/listinfo/etherlab-users