ethercatdc.c
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : ethercatdc.c
00005  * Version : 1.3.0
00006  * Date    : 24-02-2013
00007  * Copyright (C) 2005-2013 Speciaal Machinefabriek Ketels v.o.f.
00008  * Copyright (C) 2005-2013 Arthur Ketels
00009  * Copyright (C) 2008-2009 TU/e Technische Universiteit Eindhoven 
00010  *
00011  * SOEM is free software; you can redistribute it and/or modify it under
00012  * the terms of the GNU General Public License version 2 as published by the Free
00013  * Software Foundation.
00014  *
00015  * SOEM is distributed in the hope that it will be useful, but WITHOUT ANY
00016  * WARRANTY; without even the implied warranty of MERCHANTABILITY or
00017  * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License
00018  * for more details.
00019  *
00020  * As a special exception, if other files instantiate templates or use macros
00021  * or inline functions from this file, or you compile this file and link it
00022  * with other works to produce a work based on this file, this file does not
00023  * by itself cause the resulting work to be covered by the GNU General Public
00024  * License. However the source code for this file must still be made available
00025  * in accordance with section (3) of the GNU General Public License.
00026  *
00027  * This exception does not invalidate any other reasons why a work based on
00028  * this file might be covered by the GNU General Public License.
00029  *
00030  * The EtherCAT Technology, the trade name and logo “EtherCAT” are the intellectual
00031  * property of, and protected by Beckhoff Automation GmbH. You can use SOEM for
00032  * the sole purpose of creating, using and/or selling or otherwise distributing
00033  * an EtherCAT network master provided that an EtherCAT Master License is obtained
00034  * from Beckhoff Automation GmbH.
00035  *
00036  * In case you did not receive a copy of the EtherCAT Master License along with
00037  * SOEM write to Beckhoff Automation GmbH, Eiserstraße 5, D-33415 Verl, Germany
00038  * (www.beckhoff.com).
00039  */
00040 
00046 #include "ethercat_soem/oshw.h"
00047 #include "ethercat_soem/osal.h"
00048 #include "ethercat_soem/ethercattype.h"
00049 #include "ethercat_soem/ethercatbase.h"
00050 #include "ethercat_soem/ethercatmain.h"
00051 #include "ethercat_soem/ethercatdc.h"
00052 
00053 #define PORTM0 0x01
00054 #define PORTM1 0x02
00055 #define PORTM2 0x04
00056 #define PORTM3 0x08
00057 
00059 #define SyncDelay       ((int32)100000000)
00060 
00070 void ecx_dcsync0(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTime, uint32 CyclShift)
00071 {
00072    uint8 h, RA;
00073    uint16 wc, slaveh;
00074    int64 t, t1;
00075    int32 tc;
00076 
00077    slaveh = context->slavelist[slave].configadr;
00078    RA = 0;
00079 
00080    /* stop cyclic operation, ready for next trigger */
00081    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYNCACT, sizeof(RA), &RA, EC_TIMEOUTRET); 
00082    if (act)
00083    {
00084        RA = 1 + 2;    /* act cyclic operation and sync0, sync1 deactivated */
00085    }
00086    h = 0;
00087    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCCUC, sizeof(h), &h, EC_TIMEOUTRET); /* write access to ethercat */
00088    wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCSYSTIME, sizeof(t1), &t1, EC_TIMEOUTRET); /* read local time of slave */
00089    t1 = etohll(t1);
00090 
00091    /* Calculate first trigger time, always a whole multiple of CyclTime rounded up
00092    plus the shifttime (can be negative)
00093    This insures best sychronisation between slaves, slaves with the same CyclTime
00094    will sync at the same moment (you can use CyclShift to shift the sync) */
00095    if (CyclTime > 0)
00096    {
00097        t = ((t1 + SyncDelay) / CyclTime) * CyclTime + CyclTime + CyclShift;
00098    }
00099    else
00100    {
00101       t = t1 + SyncDelay + CyclShift;
00102       /* first trigger at T1 + CyclTime + SyncDelay + CyclShift in ns */
00103    }
00104    t = htoell(t);
00105    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSTART0, sizeof(t), &t, EC_TIMEOUTRET); /* SYNC0 start time */
00106    tc = htoel(CyclTime);
00107    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCCYCLE0, sizeof(tc), &tc, EC_TIMEOUTRET); /* SYNC0 cycle time */
00108    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYNCACT, sizeof(RA), &RA, EC_TIMEOUTRET); /* activate cyclic operation */
00109 }
00110 
00123 void ecx_dcsync01(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTime0, uint32 CyclTime1, uint32 CyclShift)
00124 {
00125    uint8 h, RA;
00126    uint16 wc, slaveh;
00127    int64 t, t1;
00128    int32 tc;
00129 
00130    slaveh = context->slavelist[slave].configadr;
00131    RA = 0;
00132 
00133    /* stop cyclic operation, ready for next trigger */
00134    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYNCACT, sizeof(RA), &RA, EC_TIMEOUTRET); 
00135    if (act)
00136    {
00137       RA = 1 + 2 + 4;    /* act cyclic operation and sync0 + sync1 */
00138    }
00139    h = 0;
00140    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCCUC, sizeof(h), &h, EC_TIMEOUTRET); /* write access to ethercat */
00141    wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCSYSTIME, sizeof(t1), &t1, EC_TIMEOUTRET); /* read local time of slave */
00142    t1 = etohll(t1);
00143 
00144    /* Calculate first trigger time, always a whole multiple of CyclTime rounded up
00145    plus the shifttime (can be negative)
00146    This insures best sychronisation between slaves, slaves with the same CyclTime
00147    will sync at the same moment (you can use CyclShift to shift the sync) */
00148    if (CyclTime0 > 0)
00149    {
00150       t = ((t1 + SyncDelay) / CyclTime0) * CyclTime0 + CyclTime0 + CyclShift;
00151    }
00152    else
00153    {
00154       t = t1 + SyncDelay + CyclShift;
00155       /* first trigger at T1 + CyclTime + SyncDelay + CyclShift in ns */
00156    }
00157    t = htoell(t);
00158    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSTART0, sizeof(t), &t, EC_TIMEOUTRET); /* SYNC0 start time */
00159    tc = htoel(CyclTime0);
00160    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCCYCLE0, sizeof(tc), &tc, EC_TIMEOUTRET); /* SYNC0 cycle time */
00161    tc = htoel(CyclTime1);
00162    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCCYCLE1, sizeof(tc), &tc, EC_TIMEOUTRET); /* SYNC1 cycle time */
00163    wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYNCACT, sizeof(RA), &RA, EC_TIMEOUTRET); /* activate cyclic operation */
00164 }
00165 
00166 /* latched port time of slave */
00167 static int32 ecx_porttime(ecx_contextt *context, uint16 slave, uint8 port)
00168 {
00169    int32 ts;
00170    switch (port)
00171    {
00172       case 0:
00173          ts = context->slavelist[slave].DCrtA;
00174          break;
00175       case 1:
00176          ts = context->slavelist[slave].DCrtB;
00177          break;
00178       case 2:
00179          ts = context->slavelist[slave].DCrtC;
00180          break;
00181       case 3:
00182          ts = context->slavelist[slave].DCrtD;
00183          break;
00184       default:
00185          ts = 0;
00186    }
00187    return ts;
00188 }
00189 
00190 /* calculate previous active port of a slave */
00191 static uint8 ecx_prevport(ecx_contextt *context, uint16 slave, uint8 port)
00192 {
00193    uint8 pport = port;
00194    uint8 aport = context->slavelist[slave].activeports;
00195    switch(port)
00196    {
00197       case 0:
00198          if(aport & PORTM2)
00199             pport = 2;
00200          else if (aport & PORTM1)
00201             pport = 1;
00202          else if (aport & PORTM2)
00203             pport = 3;
00204          break;
00205       case 1:
00206          if(aport & PORTM3)
00207             pport = 3;
00208          else if (aport & PORTM0)
00209             pport = 0;
00210          else if (aport & PORTM2)
00211             pport = 2;
00212          break;
00213       case 2:
00214          if(aport & PORTM1)
00215             pport = 1;
00216          else if (aport & PORTM3)
00217             pport = 3;
00218          else if (aport & PORTM0)
00219             pport = 0;
00220          break;
00221       case 3:
00222          if(aport & PORTM0)
00223             pport = 0;
00224          else if (aport & PORTM2)
00225             pport = 2;
00226          else if (aport & PORTM1)
00227             pport = 1;
00228          break;
00229    }      
00230    return pport;
00231 }
00232 
00233 /* search unconsumed ports in parent, consume and return first open port */
00234 static uint8 ecx_parentport(ecx_contextt *context, uint16 parent)
00235 {
00236    uint8 parentport = 0;
00237    uint8 b;
00238    /* search order is important, here 3 - 1 - 2 - 0 */
00239    b = context->slavelist[parent].consumedports;
00240    if (b & PORTM3)
00241    {
00242       parentport = 3;
00243       b &= (uint8)~PORTM3;
00244    }
00245    else if (b & PORTM1)
00246    {
00247       parentport = 1;
00248       b &= (uint8)~PORTM1;
00249    }
00250    else if (b & PORTM2)
00251    {
00252       parentport = 2;
00253       b &= (uint8)~PORTM2;
00254    }
00255    else if (b & PORTM0)
00256    {
00257       parentport = 0;
00258       b &= (uint8)~PORTM0;
00259    }
00260    context->slavelist[parent].consumedports = b;
00261    return parentport;
00262 }
00263 
00270 boolean ecx_configdc(ecx_contextt *context)
00271 {
00272    uint16 i, wc, slaveh, parent, child;
00273    uint16 parenthold = 0;
00274    uint16 prevDCslave = 0;
00275    int32 ht, dt1, dt2, dt3;
00276    int64 hrt;
00277    uint8 entryport;
00278    int8 nlist;
00279    int8 plist[4];
00280    int32 tlist[4];
00281 
00282    context->slavelist[0].hasdc = FALSE;
00283    context->grouplist[0].hasdc = FALSE;
00284    ht = 0;
00285    ecx_BWR(context->port, 0, ECT_REG_DCTIME0, sizeof(ht), &ht, EC_TIMEOUTRET);  /* latch DCrecvTimeA of all slaves */
00286    for (i = 1; i <= *(context->slavecount); i++)
00287    {
00288       context->slavelist[i].consumedports = context->slavelist[i].activeports;
00289       if (context->slavelist[i].hasdc)
00290       {
00291          if (!context->slavelist[0].hasdc)
00292          {
00293             context->slavelist[0].hasdc = TRUE;
00294             context->slavelist[0].DCnext = i;
00295             context->slavelist[i].DCprevious = 0;
00296             context->grouplist[0].hasdc = TRUE;
00297             context->grouplist[0].DCnext = i;
00298          }
00299          else
00300          {
00301             context->slavelist[prevDCslave].DCnext = i;
00302             context->slavelist[i].DCprevious = prevDCslave;
00303          }
00304          /* this branch has DC slave so remove parenthold */
00305          parenthold = 0;
00306          prevDCslave = i;
00307          slaveh = context->slavelist[i].configadr;
00308          wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCTIME0, sizeof(ht), &ht, EC_TIMEOUTRET);
00309          context->slavelist[i].DCrtA = etohl(ht);
00310          /* 64bit latched DCrecvTimeA of each specific slave */
00311          wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCSOF, sizeof(hrt), &hrt, EC_TIMEOUTRET);
00312          /* use it as offset in order to set local time around 0 */
00313          hrt = htoell(-etohll(hrt));
00314          /* save it in the offset register */
00315          wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYSOFFSET, sizeof(hrt), &hrt, EC_TIMEOUTRET);
00316          wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCTIME1, sizeof(ht), &ht, EC_TIMEOUTRET);
00317          context->slavelist[i].DCrtB = etohl(ht);
00318          wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCTIME2, sizeof(ht), &ht, EC_TIMEOUTRET);
00319          context->slavelist[i].DCrtC = etohl(ht);
00320          wc = ecx_FPRD(context->port, slaveh, ECT_REG_DCTIME3, sizeof(ht), &ht, EC_TIMEOUTRET);
00321          context->slavelist[i].DCrtD = etohl(ht);
00322 
00323          /* make list of active ports and their time stamps */
00324          nlist = 0;
00325          if (context->slavelist[i].activeports & PORTM0) 
00326          {
00327             plist[nlist] = 0;
00328             tlist[nlist] = context->slavelist[i].DCrtA;
00329             nlist++;
00330          }
00331          if (context->slavelist[i].activeports & PORTM3) 
00332          {
00333             plist[nlist] = 3;
00334             tlist[nlist] = context->slavelist[i].DCrtD;
00335             nlist++;
00336          }
00337          if (context->slavelist[i].activeports & PORTM1) 
00338          {
00339             plist[nlist] = 1;
00340             tlist[nlist] = context->slavelist[i].DCrtB;
00341             nlist++;
00342          }
00343          if (context->slavelist[i].activeports & PORTM2) 
00344          {
00345             plist[nlist] = 2;
00346             tlist[nlist] = context->slavelist[i].DCrtC;
00347             nlist++;
00348          }
00349          /* entryport is port with the lowest timestamp */
00350          entryport = 0;
00351          if((nlist > 1) && (tlist[1] < tlist[entryport]))
00352          {
00353             entryport = 1;
00354          }         
00355          if((nlist > 2) && (tlist[2] < tlist[entryport]))
00356          {
00357             entryport = 2;
00358          }
00359          if((nlist > 3) && (tlist[3] < tlist[entryport]))
00360          {
00361             entryport = 3;
00362          }
00363          entryport = plist[entryport];
00364          context->slavelist[i].entryport = entryport;
00365          /* consume entryport from activeports */
00366          context->slavelist[i].consumedports &= (uint8)~(1 << entryport);
00367 
00368          /* finding DC parent of current */
00369          parent = i;
00370          do
00371          {
00372             child = parent;
00373             parent = context->slavelist[parent].parent;
00374          }
00375          while (!((parent == 0) || (context->slavelist[parent].hasdc)));
00376          /* only calculate propagation delay if slave is not the first */
00377          if (parent > 0)
00378          {
00379             /* find port on parent this slave is connected to */
00380             context->slavelist[i].parentport = ecx_parentport(context, parent);
00381             if (context->slavelist[parent].topology == 1)
00382             {
00383                context->slavelist[i].parentport = context->slavelist[parent].entryport;
00384             }
00385 
00386             dt1 = 0;
00387             dt2 = 0;
00388             /* delta time of (parentport - 1) - parentport */
00389             /* note: order of ports is 0 - 3 - 1 -2 */
00390             /* non active ports are skipped */
00391             dt3 = ecx_porttime(context, parent, context->slavelist[i].parentport) -
00392                   ecx_porttime(context, parent, 
00393                     ecx_prevport(context, parent, context->slavelist[i].parentport));
00394             /* current slave has children */
00395             /* those childrens delays need to be substacted */
00396             if (context->slavelist[i].topology > 1)
00397             {
00398                dt1 = ecx_porttime(context, i, 
00399                         ecx_prevport(context, i, context->slavelist[i].entryport)) -
00400                      ecx_porttime(context, i, context->slavelist[i].entryport);
00401             }
00402             /* we are only interrested in positive diference */
00403             if (dt1 > dt3) dt1 = -dt1;
00404             /* current slave is not the first child of parent */
00405             /* previous childs delays need to be added */
00406             if ((child - parent) > 1)
00407             {
00408                dt2 = ecx_porttime(context, parent, 
00409                         ecx_prevport(context, parent, context->slavelist[i].parentport)) -
00410                      ecx_porttime(context, parent, context->slavelist[parent].entryport);
00411             }
00412             if (dt2 < 0) dt2 = -dt2;
00413 
00414             /* calculate current slave delay from delta times */
00415             /* assumption : forward delay equals return delay */
00416             context->slavelist[i].pdelay = ((dt3 - dt1) / 2) + dt2 +
00417                context->slavelist[parent].pdelay;
00418             ht = htoel(context->slavelist[i].pdelay);
00419             /* write propagation delay*/
00420             wc = ecx_FPWR(context->port, slaveh, ECT_REG_DCSYSDELAY, sizeof(ht), &ht, EC_TIMEOUTRET);
00421          }
00422       }
00423       else
00424       {
00425          context->slavelist[i].DCrtA = 0;
00426          context->slavelist[i].DCrtB = 0;
00427          context->slavelist[i].DCrtC = 0;
00428          context->slavelist[i].DCrtD = 0;
00429          parent = context->slavelist[i].parent;
00430          /* if non DC slave found on first position on branch hold root parent */
00431          if ( (parent > 0) && (context->slavelist[parent].topology > 2))
00432             parenthold = parent;
00433          /* if branch has no DC slaves consume port on root parent */
00434          if ( parenthold && (context->slavelist[i].topology == 1))
00435          {
00436             ecx_parentport(context, parenthold);
00437             parenthold = 0;
00438          }
00439       }
00440    }
00441 
00442    return context->slavelist[0].hasdc;
00443 }
00444 
00445 #ifdef EC_VER1
00446 void ec_dcsync0(uint16 slave, boolean act, uint32 CyclTime, uint32 CyclShift)
00447 {
00448    ecx_dcsync0(&ecx_context, slave, act, CyclTime, CyclShift);
00449 }
00450 
00451 void ec_dcsync01(uint16 slave, boolean act, uint32 CyclTime0, uint32 CyclTime1, uint32 CyclShift)
00452 {
00453    ecx_dcsync01(&ecx_context, slave, act, CyclTime0, CyclTime1, CyclShift);
00454 }
00455 
00456 boolean ec_configdc(void)
00457 {
00458    return ecx_configdc(&ecx_context);
00459 }
00460 #endif


ethercat_soem
Author(s): Arthur Ketels, M.J.G. van de Molengraft
autogenerated on Wed Aug 26 2015 11:32:40