ethercatmain.c
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library
00003  *
00004  * File    : ethercatmain.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 
00053 #include <stdio.h>
00054 #include <string.h>
00055 #include "ethercat_soem/osal.h"
00056 #include "ethercat_soem/oshw.h"
00057 #include "ethercat_soem/ethercattype.h"
00058 #include "ethercat_soem/ethercatbase.h"
00059 #include "ethercat_soem/ethercatmain.h"
00060 
00061 
00063 #define EC_LOCALDELAY  200
00064 
00066 PACKED_BEGIN
00067 typedef struct PACKED
00068 {
00069    uint16    comm;
00070    uint16    addr;
00071    uint16    d2;
00072 } ec_eepromt;
00073 PACKED_END
00074 
00076 PACKED_BEGIN
00077 typedef struct PACKED
00078 {
00079    ec_mbxheadert   MbxHeader;
00080    uint16          Type;
00081    uint16          Detail;
00082 } ec_mbxerrort;
00083 PACKED_END
00084 
00086 PACKED_BEGIN
00087 typedef struct PACKED
00088 {
00089    ec_mbxheadert   MbxHeader;
00090    uint16          CANOpen;
00091    uint16          ErrorCode;
00092    uint8           ErrorReg;
00093    uint8           bData;
00094    uint16          w1,w2;
00095 } ec_emcyt;
00096 PACKED_END
00097    
00098 #ifdef EC_VER1
00099 
00104 ec_slavet               ec_slave[EC_MAXSLAVE];
00106 int                     ec_slavecount;
00108 ec_groupt               ec_group[EC_MAXGROUP];
00109 
00111 static uint8            esibuf[EC_MAXEEPBUF];
00113 static uint32           esimap[EC_MAXEEPBITMAP];
00115 static ec_eringt        ec_elist;
00116 static ec_idxstackT     ec_idxstack;
00117 
00119 static ec_SMcommtypet   ec_SMcommtype;
00121 static ec_PDOassignt    ec_PDOassign;
00123 static ec_PDOdesct      ec_PDOdesc;
00124 
00126 static ec_eepromSMt     ec_SM;
00128 static ec_eepromFMMUt   ec_FMMU;
00130 boolean                 EcatError = FALSE;
00131 
00132 int64                   ec_DCtime;
00133                                                    
00134 ecx_portt               ecx_port;
00135 ecx_redportt            ecx_redport;
00136 
00137 ecx_contextt  ecx_context = {
00138     &ecx_port,       // .port          =
00139     &ec_slave[0],    // .slavelist     =
00140     &ec_slavecount,  // .slavecount    =
00141     EC_MAXSLAVE,     // .maxslave      =
00142     &ec_group[0],    // .grouplist     =
00143     EC_MAXGROUP,     // .maxgroup      =
00144     &esibuf[0],      // .esibuf        =
00145     &esimap[0],      // .esimap        =
00146     0,               // .esislave      =
00147     &ec_elist,       // .elist         =
00148     &ec_idxstack,    // .idxstack      =
00149     &EcatError,      // .ecaterror     =
00150     0,               // .DCtO          =
00151     0,               // .DCl           =
00152     &ec_DCtime,      // .DCtime        =
00153     &ec_SMcommtype,  // .SMcommtype    =
00154     &ec_PDOassign,   // .PDOassign     =
00155     &ec_PDOdesc,     // .PDOdesc       =
00156     &ec_SM,          // .eepSM         =
00157     &ec_FMMU         // .eepFMMU       =
00158 };  
00159 #endif
00160     
00165 ec_adaptert * ec_find_adapters (void)
00166 {
00167    ec_adaptert * ret_adapter;
00168 
00169    ret_adapter = oshw_find_adapters ();
00170 
00171    return ret_adapter;
00172 }
00173 
00178 void ec_free_adapters (ec_adaptert * adapter)
00179 {
00180    oshw_free_adapters (adapter);
00181 }
00182 
00188 void ecx_pusherror(ecx_contextt *context, const ec_errort *Ec)
00189 {
00190    context->elist->Error[context->elist->head] = *Ec;
00191    context->elist->Error[context->elist->head].Signal = TRUE;
00192    context->elist->head++;
00193    if (context->elist->head > EC_MAXELIST)
00194    {
00195       context->elist->head = 0;
00196    }
00197    if (context->elist->head == context->elist->tail)
00198    {
00199       context->elist->tail++;
00200    }
00201    if (context->elist->tail > EC_MAXELIST)
00202    {
00203       context->elist->tail = 0;
00204    }
00205    *(context->ecaterror) = TRUE;
00206 }
00207 
00214 boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
00215 {
00216    boolean notEmpty = (context->elist->head != context->elist->tail);
00217 
00218    *Ec = context->elist->Error[context->elist->tail];
00219    context->elist->Error[context->elist->tail].Signal = FALSE;
00220    if (notEmpty)
00221    {
00222       context->elist->tail++;
00223       if (context->elist->tail > EC_MAXELIST)
00224       {
00225          context->elist->tail = 0;
00226       }
00227    }
00228    else
00229    {
00230       *(context->ecaterror) = FALSE;
00231    }
00232    return notEmpty;
00233 }
00234 
00240 boolean ecx_iserror(ecx_contextt *context)
00241 {
00242    return (context->elist->head != context->elist->tail);
00243 }
00244 
00253 void ecx_packeterror(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
00254 {
00255    ec_errort Ec;
00256 
00257    Ec.Time = osal_current_time();
00258    Ec.Slave = Slave;
00259    Ec.Index = Index;
00260    Ec.SubIdx = SubIdx;
00261    *(context->ecaterror) = TRUE;
00262    Ec.Etype = EC_ERR_TYPE_PACKET_ERROR;
00263    Ec.ErrorCode = ErrorCode;
00264    ecx_pusherror(context, &Ec);
00265 }
00266 
00273 static void ecx_mbxerror(ecx_contextt *context, uint16 Slave,uint16 Detail)
00274 {
00275    ec_errort Ec;
00276 
00277    Ec.Time = osal_current_time();
00278    Ec.Slave = Slave;
00279    Ec.Index = 0;
00280    Ec.SubIdx = 0;
00281    Ec.Etype = EC_ERR_TYPE_MBX_ERROR;
00282    Ec.ErrorCode = Detail;
00283    ecx_pusherror(context, &Ec);
00284 }
00285 
00296 static void ecx_mbxemergencyerror(ecx_contextt *context, uint16 Slave,uint16 ErrorCode,uint16 ErrorReg,
00297     uint8 b1, uint16 w1, uint16 w2)
00298 {
00299    ec_errort Ec;
00300 
00301    Ec.Time = osal_current_time();
00302    Ec.Slave = Slave;
00303    Ec.Index = 0;
00304    Ec.SubIdx = 0;
00305    Ec.Etype = EC_ERR_TYPE_EMERGENCY;
00306    Ec.ErrorCode = ErrorCode;
00307    Ec.ErrorReg = (uint8)ErrorReg;
00308    Ec.b1 = b1;
00309    Ec.w1 = w1;
00310    Ec.w2 = w2;
00311    ecx_pusherror(context, &Ec);
00312 }
00313 
00319 int ecx_init(ecx_contextt *context, char * ifname)
00320 {
00321    return ecx_setupnic(context->port, ifname, FALSE);
00322 }
00323 
00331 int ecx_init_redundant(ecx_contextt *context, ecx_redportt *redport, char *ifname, char *if2name)
00332 {
00333    int rval, zbuf;
00334    ec_etherheadert *ehp;
00335 
00336    context->port->redport = redport;
00337    ecx_setupnic(context->port, ifname, FALSE);
00338    rval = ecx_setupnic(context->port, if2name, TRUE);
00339    /* prepare "dummy" BRD tx frame for redundant operation */
00340    ehp = (ec_etherheadert *)&(context->port->txbuf2);
00341    ehp->sa1 = oshw_htons(secMAC[0]);
00342    zbuf = 0;
00343    ecx_setupdatagram(context->port, &(context->port->txbuf2), EC_CMD_BRD, 0, 0x0000, 0x0000, 2, &zbuf);
00344    context->port->txbuflength2 = ETH_HEADERSIZE + EC_HEADERSIZE + EC_WKCSIZE + 2;
00345 
00346    return rval;
00347 }
00348 
00352 void ecx_close(ecx_contextt *context)
00353 {
00354    ecx_closenic(context->port);
00355 };
00356 
00365 uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address)
00366 {
00367    uint16 configadr, eadr;
00368    uint64 edat;
00369    uint16 mapw, mapb;
00370    int lp,cnt;
00371    uint8 retval;
00372 
00373    retval = 0xff;
00374    if (slave != context->esislave) /* not the same slave? */
00375    {
00376       memset(context->esimap, 0x00, EC_MAXEEPBITMAP); /* clear esibuf cache map */
00377       context->esislave = slave;
00378    }
00379    if (address < EC_MAXEEPBUF)
00380    {
00381       mapw = address >> 5;
00382       mapb = address - (mapw << 5);
00383       if (context->esimap[mapw] & (uint32)(1 << mapb))
00384       {
00385          /* byte is already in buffer */
00386          retval = context->esibuf[address];
00387       }
00388       else
00389       {
00390          /* byte is not in buffer, put it there */
00391          configadr = context->slavelist[slave].configadr;
00392          ecx_eeprom2master(context, slave); /* set eeprom control to master */
00393          eadr = address >> 1;
00394          edat = ecx_readeepromFP (context, configadr, eadr, EC_TIMEOUTEEP);
00395          /* 8 byte response */
00396          if (context->slavelist[slave].eep_8byte)
00397          {
00398             put_unaligned64(edat, &(context->esibuf[eadr << 1]));
00399             cnt = 8;
00400          }
00401          /* 4 byte response */
00402          else
00403          {
00404             put_unaligned32(edat, &(context->esibuf[eadr << 1]));
00405             cnt = 4;
00406          }
00407          /* find bitmap location */
00408          mapw = eadr >> 4;
00409          mapb = (eadr << 1) - (mapw << 5);
00410          for(lp = 0 ; lp < cnt ; lp++)
00411          {
00412             /* set bitmap for each byte that is read */
00413             context->esimap[mapw] |= (1 << mapb);
00414             mapb++;
00415             if (mapb > 31)
00416             {
00417                mapb = 0;
00418                mapw++;
00419             }
00420          }
00421          retval = context->esibuf[address];
00422       }
00423    }
00424 
00425    return retval;
00426 }
00427 
00434 int16 ecx_siifind(ecx_contextt *context, uint16 slave, uint16 cat)
00435 {
00436    int16 a;
00437    uint16 p;
00438    uint8 eectl = context->slavelist[slave].eep_pdi;
00439 
00440    a = ECT_SII_START << 1;
00441    /* read first SII section category */
00442    p = ecx_siigetbyte(context, slave, a++);
00443    p += (ecx_siigetbyte(context, slave, a++) << 8);
00444    /* traverse SII while category is not found and not EOF */
00445    while ((p != cat) && (p != 0xffff))
00446    {
00447       /* read section length */
00448       p = ecx_siigetbyte(context, slave, a++);
00449       p += (ecx_siigetbyte(context, slave, a++) << 8);
00450       /* locate next section category */
00451       a += p << 1;
00452       /* read section category */
00453       p = ecx_siigetbyte(context, slave, a++);
00454       p += (ecx_siigetbyte(context, slave, a++) << 8);
00455    }
00456    if (p != cat)
00457    {
00458       a = 0;
00459    }
00460    if (eectl)
00461    {
00462       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00463    }
00464 
00465    return a;
00466 }
00467 
00474 void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
00475 {
00476    uint16 a,i,j,l,n,ba;
00477    char *ptr;
00478    uint8 eectl = context->slavelist[slave].eep_pdi;
00479 
00480    ptr = str;
00481    a = ecx_siifind (context, slave, ECT_SII_STRING); /* find string section */
00482    if (a > 0)
00483    {
00484       ba = a + 2; /* skip SII section header */
00485       n = ecx_siigetbyte(context, slave, ba++); /* read number of strings in section */
00486       if (Sn <= n) /* is req string available? */
00487       {
00488          for (i = 1; i <= Sn; i++) /* walk through strings */
00489          {
00490             l = ecx_siigetbyte(context, slave, ba++); /* length of this string */
00491             if (i < Sn)
00492             {
00493                ba += l;
00494             }
00495             else
00496             {
00497                ptr = str;
00498                for (j = 1; j <= l; j++) /* copy one string */
00499                {
00500                   if(j <= EC_MAXNAME)
00501                   {
00502                      *ptr = (char)ecx_siigetbyte(context, slave, ba++);
00503                      ptr++;
00504                   }
00505                   else
00506                   {
00507                      ba++;
00508                   }
00509                }
00510             }
00511          }
00512          *ptr = 0; /* add zero terminator */
00513       }
00514       else
00515       {
00516          ptr = str;
00517          *ptr = 0; /* empty string */
00518       }
00519    }
00520    if (eectl)
00521    {
00522       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00523    }
00524 }
00525 
00532 uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt* FMMU)
00533 {
00534    uint16  a;
00535    uint8 eectl = context->slavelist[slave].eep_pdi;
00536 
00537    FMMU->nFMMU = 0;
00538    FMMU->FMMU0 = 0;
00539    FMMU->FMMU1 = 0;
00540    FMMU->FMMU2 = 0;
00541    FMMU->FMMU3 = 0;
00542    FMMU->Startpos = ecx_siifind(context, slave, ECT_SII_FMMU);
00543 
00544    if (FMMU->Startpos > 0)
00545    {
00546       a = FMMU->Startpos;
00547       FMMU->nFMMU = ecx_siigetbyte(context, slave, a++);
00548       FMMU->nFMMU += (ecx_siigetbyte(context, slave, a++) << 8);
00549       FMMU->nFMMU *= 2;
00550       FMMU->FMMU0 = ecx_siigetbyte(context, slave, a++);
00551       FMMU->FMMU1 = ecx_siigetbyte(context, slave, a++);
00552       if (FMMU->nFMMU > 2)
00553       {
00554          FMMU->FMMU2 = ecx_siigetbyte(context, slave, a++);
00555          FMMU->FMMU3 = ecx_siigetbyte(context, slave, a++);
00556       }
00557    }
00558    if (eectl)
00559    {
00560       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00561    }
00562 
00563    return FMMU->nFMMU;
00564 }
00565 
00572 uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM)
00573 {
00574    uint16 a,w;
00575    uint8 eectl = context->slavelist[slave].eep_pdi;
00576 
00577    SM->nSM = 0;
00578    SM->Startpos = ecx_siifind(context, slave, ECT_SII_SM);
00579    if (SM->Startpos > 0)
00580    {
00581       a = SM->Startpos;
00582       w = ecx_siigetbyte(context, slave, a++);
00583       w += (ecx_siigetbyte(context, slave, a++) << 8);
00584       SM->nSM = (w / 4);
00585       SM->PhStart = ecx_siigetbyte(context, slave, a++);
00586       SM->PhStart += (ecx_siigetbyte(context, slave, a++) << 8);
00587       SM->Plength = ecx_siigetbyte(context, slave, a++);
00588       SM->Plength += (ecx_siigetbyte(context, slave, a++) << 8);
00589       SM->Creg = ecx_siigetbyte(context, slave, a++);
00590       SM->Sreg = ecx_siigetbyte(context, slave, a++);
00591       SM->Activate = ecx_siigetbyte(context, slave, a++);
00592       SM->PDIctrl = ecx_siigetbyte(context, slave, a++);
00593    }
00594    if (eectl)
00595    {
00596       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00597    }
00598 
00599    return SM->nSM;
00600 }
00601 
00609 uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint16 n)
00610 {
00611    uint16 a;
00612    uint16 retVal = 0;
00613    uint8 eectl = context->slavelist[slave].eep_pdi;
00614 
00615    if (n < SM->nSM)
00616    {
00617       a = SM->Startpos + 2 + (n * 8);
00618       SM->PhStart = ecx_siigetbyte(context, slave, a++);
00619       SM->PhStart += (ecx_siigetbyte(context, slave, a++) << 8);
00620       SM->Plength = ecx_siigetbyte(context, slave, a++);
00621       SM->Plength += (ecx_siigetbyte(context, slave, a++) << 8);
00622       SM->Creg = ecx_siigetbyte(context, slave, a++);
00623       SM->Sreg = ecx_siigetbyte(context, slave, a++);
00624       SM->Activate = ecx_siigetbyte(context, slave, a++);
00625       SM->PDIctrl = ecx_siigetbyte(context, slave, a++);
00626       retVal = 1;
00627    }
00628    if (eectl)
00629    {
00630       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00631    }
00632 
00633    return retVal;
00634 }
00635 
00643 int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t)
00644 {
00645    uint16 a , w, c, e, er, Size;
00646    uint8 eectl = context->slavelist[slave].eep_pdi;
00647 
00648    Size = 0;
00649    PDO->nPDO = 0;
00650    PDO->Length = 0;
00651    PDO->Index[1] = 0;
00652    for (c = 0 ; c < EC_MAXSM ; c++) PDO->SMbitsize[c] = 0;
00653    if (t > 1)
00654       t = 1;
00655    PDO->Startpos = ecx_siifind(context, slave, ECT_SII_PDO + t);
00656    if (PDO->Startpos > 0)
00657    {
00658       a = PDO->Startpos;
00659       w = ecx_siigetbyte(context, slave, a++);
00660       w += (ecx_siigetbyte(context, slave, a++) << 8);
00661       PDO->Length = w;
00662       c = 1;
00663       /* traverse through all PDOs */
00664       do
00665       {
00666          PDO->nPDO++;
00667          PDO->Index[PDO->nPDO] = ecx_siigetbyte(context, slave, a++);
00668          PDO->Index[PDO->nPDO] += (ecx_siigetbyte(context, slave, a++) << 8);
00669          PDO->BitSize[PDO->nPDO] = 0;
00670          c++;
00671          e = ecx_siigetbyte(context, slave, a++);
00672          PDO->SyncM[PDO->nPDO] = ecx_siigetbyte(context, slave, a++);
00673          a += 4;
00674          c += 2;
00675          if (PDO->SyncM[PDO->nPDO] < EC_MAXSM) /* active and in range SM? */
00676          {
00677             /* read all entries defined in PDO */
00678             for (er = 1; er <= e; er++)
00679             {
00680                c += 4;
00681                a += 5;
00682                PDO->BitSize[PDO->nPDO] += ecx_siigetbyte(context, slave, a++);
00683                a += 2;
00684             }
00685             PDO->SMbitsize[ PDO->SyncM[PDO->nPDO] ] += PDO->BitSize[PDO->nPDO];
00686             Size += PDO->BitSize[PDO->nPDO];
00687             c++;
00688          }
00689          else /* PDO deactivated because SM is 0xff or > EC_MAXSM */
00690          {
00691             c += 4 * e;
00692             a += 8 * e;
00693             c++;
00694          }
00695          if (PDO->nPDO >= (EC_MAXEEPDO - 1))
00696          {
00697             c = PDO->Length; /* limit number of PDO entries in buffer */
00698          }
00699       }
00700       while (c < PDO->Length);
00701    }
00702    if (eectl)
00703    {
00704       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
00705    }
00706 
00707    return (Size);
00708 }
00709 
00714 int ecx_readstate(ecx_contextt *context)
00715 {
00716    uint16 slave, configadr, lowest, rval;
00717    ec_alstatust slstat;
00718 
00719    lowest = 0xff;
00720    context->slavelist[0].ALstatuscode = 0;
00721    for (slave = 1; slave <= *(context->slavecount); slave++)
00722    {
00723       configadr = context->slavelist[slave].configadr;
00724       slstat.alstatus = 0;
00725       slstat.alstatuscode = 0;
00726       ecx_FPRD(context->port, configadr, ECT_REG_ALSTAT, sizeof(slstat), &slstat, EC_TIMEOUTRET3);
00727       rval = etohs(slstat.alstatus);
00728       context->slavelist[slave].ALstatuscode = etohs(slstat.alstatuscode);
00729       if (rval < lowest)
00730       {
00731          lowest = rval;
00732       }
00733       context->slavelist[slave].state = rval;
00734       context->slavelist[0].ALstatuscode |= context->slavelist[slave].ALstatuscode;
00735    }
00736    context->slavelist[0].state = lowest;
00737 
00738    return lowest;
00739 }
00740 
00747 int ecx_writestate(ecx_contextt *context, uint16 slave)
00748 {
00749    uint16 configadr, slstate;
00750 
00751    if (slave == 0)
00752    {
00753       slstate = htoes(context->slavelist[slave].state);
00754       ecx_BWR(context->port, 0, ECT_REG_ALCTL, sizeof(slstate), &slstate, EC_TIMEOUTRET3); /* write slave status */
00755    }
00756    else
00757    {
00758       configadr = context->slavelist[slave].configadr;
00759 
00760       ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(context->slavelist[slave].state), EC_TIMEOUTRET3); /* write slave status */
00761    }
00762    return 0;
00763 }
00764 
00773 uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
00774 {
00775    uint16 configadr, state, rval;
00776    ec_alstatust slstat;
00777    osal_timert timer;
00778 
00779    if ( slave > *(context->slavecount) )
00780    {
00781       return 0;
00782    }
00783    osal_timer_start(&timer, timeout);
00784    configadr = context->slavelist[slave].configadr;
00785    do
00786    {
00787       if (slave < 1)
00788       {
00789          rval = 0;
00790          ecx_BRD(context->port, 0, ECT_REG_ALSTAT, sizeof(rval), &rval , EC_TIMEOUTRET);
00791          rval = etohs(rval);
00792       }
00793       else
00794       {
00795          slstat.alstatus = 0;
00796          slstat.alstatuscode = 0;
00797          ecx_FPRD(context->port, configadr, ECT_REG_ALSTAT, sizeof(slstat), &slstat, EC_TIMEOUTRET);
00798          rval = etohs(slstat.alstatus);
00799          context->slavelist[slave].ALstatuscode = etohs(slstat.alstatuscode);
00800       }
00801       state = rval & 0x000f; /* read slave status */
00802       if (state != reqstate)
00803       {
00804          osal_usleep(1000);
00805       }
00806    }
00807    while ((state != reqstate) && (osal_timer_is_expired(&timer) == FALSE));
00808    context->slavelist[slave].state = rval;
00809 
00810    return state;
00811 }
00812 
00818 uint8 ec_nextmbxcnt(uint8 cnt)
00819 {
00820    cnt++;
00821    if (cnt > 7)
00822    {
00823       cnt = 1; /* wrap around to 1, not 0 */
00824    }
00825 
00826    return cnt;
00827 }
00828 
00832 void ec_clearmbx(ec_mbxbuft *Mbx)
00833 {
00834     memset(*Mbx, 0x00, EC_MAXMBX);
00835 }
00836 
00843 int ecx_mbxempty(ecx_contextt *context, uint16 slave, int timeout)
00844 {
00845    uint16 configadr;
00846    uint8 SMstat;
00847    int wkc;
00848    osal_timert timer;
00849 
00850    osal_timer_start(&timer, timeout);
00851    configadr = context->slavelist[slave].configadr;
00852    do
00853    {
00854       wkc = ecx_FPRD(context->port, configadr, ECT_REG_SM0STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
00855       SMstat = etohs(SMstat);
00856       if (((SMstat & 0x08) != 0) && (timeout > EC_LOCALDELAY))
00857       {
00858          osal_usleep(EC_LOCALDELAY);
00859       }
00860    }
00861    while (((wkc <= 0) || ((SMstat & 0x08) != 0)) && (osal_timer_is_expired(&timer) == FALSE));
00862 
00863    if ((wkc > 0) && ((SMstat & 0x08) == 0))
00864    {
00865       return 1;
00866    }
00867 
00868    return 0;
00869 }
00870 
00878 int ecx_mbxsend(ecx_contextt *context, uint16 slave,ec_mbxbuft *mbx, int timeout)
00879 {
00880    uint16 mbxwo,mbxl,configadr;
00881    int wkc;
00882 
00883    wkc = 0;
00884    configadr = context->slavelist[slave].configadr;
00885    mbxl = context->slavelist[slave].mbx_l;
00886    if (mbxl > 0)
00887    {
00888       if (ecx_mbxempty(context, slave, timeout))
00889       {
00890          mbxwo = context->slavelist[slave].mbx_wo;
00891          /* write slave in mailbox */
00892          wkc = ecx_FPWR(context->port, configadr, mbxwo, mbxl, mbx, EC_TIMEOUTRET3);
00893       }
00894       else
00895       {
00896          wkc = 0;
00897       }
00898    }
00899 
00900    return wkc;
00901 }
00902 
00911 int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
00912 {
00913    uint16 mbxro,mbxl,configadr;
00914    int wkc=0;
00915    int wkc2;
00916    uint16 SMstat;
00917    uint8 SMcontr;
00918    ec_mbxheadert *mbxh;
00919    ec_emcyt *EMp;
00920    ec_mbxerrort *MBXEp;
00921 
00922    configadr = context->slavelist[slave].configadr;
00923    mbxl = context->slavelist[slave].mbx_rl;
00924    if (mbxl > 0)
00925    {
00926       osal_timert timer;
00927 
00928       osal_timer_start(&timer, timeout);
00929       wkc = 0;
00930       do /* wait for read mailbox available */
00931       {
00932          wkc = ecx_FPRD(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
00933          SMstat = etohs(SMstat);
00934          if (((SMstat & 0x08) == 0) && (timeout > EC_LOCALDELAY))
00935          {
00936             osal_usleep(EC_LOCALDELAY);
00937          }
00938       }
00939       while (((wkc <= 0) || ((SMstat & 0x08) == 0)) && (osal_timer_is_expired(&timer) == FALSE));
00940 
00941       if ((wkc > 0) && ((SMstat & 0x08) > 0)) /* read mailbox available ? */
00942       {
00943          mbxro = context->slavelist[slave].mbx_ro;
00944          mbxh = (ec_mbxheadert *)mbx;
00945          do
00946          {
00947             wkc = ecx_FPRD(context->port, configadr, mbxro, mbxl, mbx, EC_TIMEOUTRET); /* get mailbox */
00948             if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == 0x00)) /* Mailbox error response? */
00949             {
00950                MBXEp = (ec_mbxerrort *)mbx;
00951                ecx_mbxerror(context, slave, etohs(MBXEp->Detail));
00952                wkc = 0; /* prevent emergency to cascade up, it is already handled. */
00953             }
00954             else if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == 0x03)) /* CoE response? */
00955             {
00956                EMp = (ec_emcyt *)mbx;
00957                if ((etohs(EMp->CANOpen) >> 12) == 0x01) /* Emergency request? */
00958                {
00959                   ecx_mbxemergencyerror(context, slave, etohs(EMp->ErrorCode), EMp->ErrorReg,
00960                           EMp->bData, etohs(EMp->w1), etohs(EMp->w2));
00961                   wkc = 0; /* prevent emergency to cascade up, it is already handled. */
00962                }
00963             }
00964             else
00965             {
00966                if (wkc <= 0) /* read mailbox lost */
00967                {
00968                   SMstat ^= 0x0200; /* toggle repeat request */
00969                   SMstat = htoes(SMstat);
00970                   wkc2 = ecx_FPWR(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
00971                   SMstat = etohs(SMstat);
00972                   do /* wait for toggle ack */
00973                   {
00974                      wkc2 = ecx_FPRD(context->port, configadr, ECT_REG_SM1CONTR, sizeof(SMcontr), &SMcontr, EC_TIMEOUTRET);
00975                    } while (((wkc2 <= 0) || ((SMcontr & 0x02) != (HI_BYTE(SMstat) & 0x02))) && (osal_timer_is_expired(&timer) == FALSE));
00976                   do /* wait for read mailbox available */
00977                   {
00978                      wkc2 = ecx_FPRD(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
00979                      SMstat = etohs(SMstat);
00980                      if (((SMstat & 0x08) == 0) && (timeout > EC_LOCALDELAY))
00981                      {
00982                         osal_usleep(EC_LOCALDELAY);
00983                      }
00984                   } while (((wkc2 <= 0) || ((SMstat & 0x08) == 0)) && (osal_timer_is_expired(&timer) == FALSE));
00985                }
00986             }
00987          } while ((wkc <= 0) && (osal_timer_is_expired(&timer) == FALSE)); /* if WKC<=0 repeat */
00988       }
00989       else /* no read mailbox available */
00990       {
00991           wkc = 0;
00992       }
00993    }
00994 
00995    return wkc;
00996 }
00997 
01003 void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf)
01004 {
01005    int address, incr;
01006    uint16 configadr;
01007    uint64 *p64;
01008    uint16 *p16;
01009    uint64 edat;
01010    uint8 eectl = context->slavelist[slave].eep_pdi;
01011 
01012    ecx_eeprom2master(context, slave); /* set eeprom control to master */
01013    configadr = context->slavelist[slave].configadr;
01014    address = ECT_SII_START;
01015    p16=(uint16*)esibuf;
01016    if (context->slavelist[slave].eep_8byte)
01017    {
01018       incr = 4;
01019    }
01020    else
01021    {
01022       incr = 2;
01023    }
01024    do
01025    {
01026       edat = ecx_readeepromFP(context, configadr, address, EC_TIMEOUTEEP);
01027       p64 = (uint64*)p16;
01028       *p64 = edat;
01029       p16 += incr;
01030       address += incr;
01031    } while ((address <= (EC_MAXEEPBUF >> 1)) && ((uint32)edat != 0xffffffff));
01032 
01033    if (eectl)
01034    {
01035       ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
01036    }
01037 }
01038 
01046 uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
01047 {
01048    uint16 configadr;
01049 
01050    ecx_eeprom2master(context, slave); /* set eeprom control to master */
01051    configadr = context->slavelist[slave].configadr;
01052 
01053    return ((uint32)ecx_readeepromFP(context, configadr, eeproma, timeout));
01054 }
01055 
01064 int ecx_writeeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout)
01065 {
01066    uint16 configadr;
01067 
01068    ecx_eeprom2master(context, slave); /* set eeprom control to master */
01069    configadr = context->slavelist[slave].configadr;
01070    return (ecx_writeeepromFP(context, configadr, eeproma, data, timeout));
01071 }
01072 
01078 int ecx_eeprom2master(ecx_contextt *context, uint16 slave)
01079 {
01080    int wkc = 1, cnt = 0;
01081    uint16 configadr;
01082    uint8 eepctl;
01083 
01084    if ( context->slavelist[slave].eep_pdi )
01085    {
01086       configadr = context->slavelist[slave].configadr;
01087       eepctl = 2;
01088       do
01089       {
01090          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* force Eeprom from PDI */
01091       }
01092       while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01093       eepctl = 0;
01094       cnt = 0;
01095       do
01096       {
01097          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* set Eeprom to master */
01098       }
01099       while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01100       context->slavelist[slave].eep_pdi = 0;
01101    }
01102 
01103    return wkc;
01104 }
01105 
01111 int ecx_eeprom2pdi(ecx_contextt *context, uint16 slave)
01112 {
01113    int wkc = 1, cnt = 0;
01114    uint16 configadr;
01115    uint8 eepctl;
01116 
01117    if ( !context->slavelist[slave].eep_pdi )
01118    {
01119       configadr = context->slavelist[slave].configadr;
01120       eepctl = 1;
01121       do
01122       {
01123          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* set Eeprom to PDI */
01124       }
01125       while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01126       context->slavelist[slave].eep_pdi = 1;
01127    }
01128 
01129    return wkc;
01130 }
01131 
01132 uint16 ecx_eeprom_waitnotbusyAP(ecx_contextt *context, uint16 aiadr,uint16 *estat, int timeout)
01133 {
01134    int wkc, cnt = 0, retval = 0;
01135    osal_timert timer;
01136 
01137    osal_timer_start(&timer, timeout);
01138    do
01139    {
01140       if (cnt++)
01141       {
01142          osal_usleep(EC_LOCALDELAY);
01143       }
01144       wkc=ecx_APRD(context->port, aiadr, ECT_REG_EEPSTAT, sizeof(*estat), estat, EC_TIMEOUTRET);
01145       *estat = etohs(*estat);
01146    }
01147    while (((wkc <= 0) || ((*estat & EC_ESTAT_BUSY) > 0)) && (osal_timer_is_expired(&timer) == FALSE)); /* wait for eeprom ready */
01148    if ((*estat & EC_ESTAT_BUSY) == 0)
01149    {
01150       retval = 1;
01151    }
01152 
01153    return retval;
01154 }
01155 
01163 uint64 ecx_readeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout)
01164 {
01165    uint16 estat;
01166    uint32 edat32;
01167    uint64 edat64;
01168    ec_eepromt ed;
01169    int wkc, cnt, nackcnt = 0;
01170 
01171    edat64 = 0;
01172    edat32 = 0;
01173    if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
01174    {
01175       if (estat & EC_ESTAT_EMASK) /* error bits are set */
01176       {
01177          estat = htoes(EC_ECMD_NOP); /* clear error bits */
01178          wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
01179       }
01180 
01181       do
01182       {
01183          ed.comm = htoes(EC_ECMD_READ);
01184          ed.addr = htoes(eeproma);
01185          ed.d2   = 0x0000;
01186          cnt = 0;
01187          do
01188          {
01189             wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
01190          }
01191          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01192          if (wkc)
01193          {
01194             osal_usleep(EC_LOCALDELAY);
01195             estat = 0x0000;
01196             if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
01197             {
01198                if (estat & EC_ESTAT_NACK)
01199                {
01200                   nackcnt++;
01201                   osal_usleep(EC_LOCALDELAY * 5);
01202                }
01203                else
01204                {
01205                   nackcnt = 0;
01206                   if (estat & EC_ESTAT_R64)
01207                   {
01208                      cnt = 0;
01209                      do
01210                      {
01211                         wkc = ecx_APRD(context->port, aiadr, ECT_REG_EEPDAT, sizeof(edat64), &edat64, EC_TIMEOUTRET);
01212                      }
01213                      while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01214                   }
01215                   else
01216                   {
01217                      cnt = 0;
01218                      do
01219                      {
01220                         wkc = ecx_APRD(context->port, aiadr, ECT_REG_EEPDAT, sizeof(edat32), &edat32, EC_TIMEOUTRET);
01221                      }
01222                      while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01223                      edat64=(uint64)edat32;
01224                   }
01225                }
01226             }
01227          }
01228       }
01229       while ((nackcnt > 0) && (nackcnt < 3));
01230    }
01231 
01232    return edat64;
01233 }
01234 
01243 int ecx_writeeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
01244 {
01245    uint16 estat;
01246    ec_eepromt ed;
01247    int wkc, rval = 0, cnt = 0, nackcnt = 0;
01248 
01249    if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
01250    {
01251       if (estat & EC_ESTAT_EMASK) /* error bits are set */
01252       {
01253          estat = htoes(EC_ECMD_NOP); /* clear error bits */
01254          wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
01255       }
01256       do
01257       {
01258          cnt = 0;
01259          do
01260          {
01261             wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPDAT, sizeof(data), &data, EC_TIMEOUTRET);
01262          }
01263          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01264 
01265          ed.comm = EC_ECMD_WRITE;
01266          ed.addr = eeproma;
01267          ed.d2   = 0x0000;
01268          cnt = 0;
01269          do
01270          {
01271             wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
01272          }
01273          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01274          if (wkc)
01275          {
01276             osal_usleep(EC_LOCALDELAY * 2);
01277             estat = 0x0000;
01278             if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
01279             {
01280                if (estat & EC_ESTAT_NACK)
01281                {
01282                   nackcnt++;
01283                   osal_usleep(EC_LOCALDELAY * 5);
01284                }
01285                else
01286                {
01287                   nackcnt = 0;
01288                   rval = 1;
01289                }
01290             }
01291          }
01292 
01293       }
01294       while ((nackcnt > 0) && (nackcnt < 3));
01295    }
01296 
01297    return rval;
01298 }
01299 
01300 uint16 ecx_eeprom_waitnotbusyFP(ecx_contextt *context, uint16 configadr,uint16 *estat, int timeout)
01301 {
01302    int wkc, cnt = 0, retval = 0;
01303    osal_timert timer;
01304 
01305    osal_timer_start(&timer, timeout);
01306    do
01307    {
01308       if (cnt++)
01309       {
01310          osal_usleep(EC_LOCALDELAY);
01311       }
01312       wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPSTAT, sizeof(*estat), estat, EC_TIMEOUTRET);
01313       *estat = etohs(*estat);
01314    }
01315    while (((wkc <= 0) || ((*estat & EC_ESTAT_BUSY) > 0)) && (osal_timer_is_expired(&timer) == FALSE)); /* wait for eeprom ready */
01316    if ((*estat & EC_ESTAT_BUSY) == 0)
01317    {
01318       retval = 1;
01319    }
01320 
01321    return retval;
01322 }
01323 
01331 uint64 ecx_readeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout)
01332 {
01333    uint16 estat;
01334    uint32 edat32;
01335    uint64 edat64;
01336    ec_eepromt ed;
01337    int wkc, cnt, nackcnt = 0;
01338 
01339    edat64 = 0;
01340    edat32 = 0;
01341    if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
01342    {
01343       if (estat & EC_ESTAT_EMASK) /* error bits are set */
01344       {
01345          estat = htoes(EC_ECMD_NOP); /* clear error bits */
01346          wkc=ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
01347       }
01348 
01349       do
01350       {
01351          ed.comm = htoes(EC_ECMD_READ);
01352          ed.addr = htoes(eeproma);
01353          ed.d2   = 0x0000;
01354          cnt = 0;
01355          do
01356          {
01357             wkc=ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
01358          }
01359          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01360          if (wkc)
01361          {
01362             osal_usleep(EC_LOCALDELAY);
01363             estat = 0x0000;
01364             if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
01365             {
01366                if (estat & EC_ESTAT_NACK)
01367                {
01368                   nackcnt++;
01369                   osal_usleep(EC_LOCALDELAY * 5);
01370                }
01371                else
01372                {
01373                   nackcnt = 0;
01374                   if (estat & EC_ESTAT_R64)
01375                   {
01376                      cnt = 0;
01377                      do
01378                      {
01379                         wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat64), &edat64, EC_TIMEOUTRET);
01380                      }
01381                      while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01382                   }
01383                   else
01384                   {
01385                      cnt = 0;
01386                      do
01387                      {
01388                         wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat32), &edat32, EC_TIMEOUTRET);
01389                      }
01390                      while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01391                      edat64=(uint64)edat32;
01392                   }
01393                }
01394             }
01395          }
01396       }
01397       while ((nackcnt > 0) && (nackcnt < 3));
01398    }
01399 
01400    return edat64;
01401 }
01402 
01411 int ecx_writeeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout)
01412 {
01413    uint16 estat;
01414    ec_eepromt ed;
01415    int wkc, rval = 0, cnt = 0, nackcnt = 0;
01416 
01417    if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
01418    {
01419       if (estat & EC_ESTAT_EMASK) /* error bits are set */
01420       {
01421          estat = htoes(EC_ECMD_NOP); /* clear error bits */
01422          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
01423       }
01424       do
01425       {
01426          cnt = 0;
01427          do
01428          {
01429             wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPDAT, sizeof(data), &data, EC_TIMEOUTRET);
01430          }
01431          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01432          ed.comm = EC_ECMD_WRITE;
01433          ed.addr = eeproma;
01434          ed.d2   = 0x0000;
01435          cnt = 0;
01436          do
01437          {
01438             wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
01439          }
01440          while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01441          if (wkc)
01442          {
01443             osal_usleep(EC_LOCALDELAY * 2);
01444             estat = 0x0000;
01445             if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
01446             {
01447                if (estat & EC_ESTAT_NACK)
01448                {
01449                   nackcnt++;
01450                   osal_usleep(EC_LOCALDELAY * 5);
01451                }
01452                else
01453                {
01454                   nackcnt = 0;
01455                   rval = 1;
01456                }
01457             }
01458          }
01459       }
01460       while ((nackcnt > 0) && (nackcnt < 3));
01461    }
01462 
01463    return rval;
01464 }
01465 
01472 void ecx_readeeprom1(ecx_contextt *context, uint16 slave, uint16 eeproma)
01473 {
01474    uint16 configadr, estat;
01475    ec_eepromt ed;
01476    int wkc, cnt = 0;
01477 
01478    ecx_eeprom2master(context, slave); /* set eeprom control to master */
01479    configadr = context->slavelist[slave].configadr;
01480    if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, EC_TIMEOUTEEP))
01481    {
01482       if (estat & EC_ESTAT_EMASK) /* error bits are set */
01483       {
01484          estat = htoes(EC_ECMD_NOP); /* clear error bits */
01485          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
01486       }
01487       ed.comm = htoes(EC_ECMD_READ);
01488       ed.addr = htoes(eeproma);
01489       ed.d2   = 0x0000;
01490       do
01491       {
01492          wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
01493       }
01494       while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01495    }
01496 }
01497 
01505 uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout)
01506 {
01507    uint16 estat, configadr;
01508    uint32 edat;
01509    int wkc, cnt = 0;
01510 
01511    configadr = context->slavelist[slave].configadr;
01512    edat = 0;
01513    estat = 0x0000;
01514    if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
01515    {
01516       do
01517       {
01518           wkc = ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat), &edat, EC_TIMEOUTRET);
01519       }
01520       while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
01521    }
01522 
01523    return edat;
01524 }
01525 
01532 static void ecx_pushindex(ecx_contextt *context, uint8 idx, void *data, uint16 length)
01533 {
01534    if(context->idxstack->pushed < EC_MAXBUF)
01535    {
01536       context->idxstack->idx[context->idxstack->pushed] = idx;
01537       context->idxstack->data[context->idxstack->pushed] = data;
01538       context->idxstack->length[context->idxstack->pushed] = length;
01539       context->idxstack->pushed++;
01540    }
01541 }
01542 
01547 static int ecx_pullindex(ecx_contextt *context)
01548 {
01549    int rval = -1;
01550    if(context->idxstack->pulled < context->idxstack->pushed)
01551    {
01552       rval = context->idxstack->pulled;
01553       context->idxstack->pulled++;
01554    }
01555 
01556    return rval;
01557 }
01558 
01571 int ecx_send_processdata_group(ecx_contextt *context, uint8 group)
01572 {
01573    uint32 LogAdr;
01574    uint16 w1, w2;
01575    int length, sublength;
01576    uint8 idx;
01577    int wkc;
01578    uint8* data;
01579    boolean first=FALSE;
01580    uint16 currentsegment = 0;
01581 
01582    wkc = 0;
01583    if(context->grouplist[group].hasdc)
01584    {
01585       first = TRUE;
01586    }
01587    length = context->grouplist[group].Obytes + context->grouplist[group].Ibytes;
01588    LogAdr = context->grouplist[group].logstartaddr;
01589    if (length)
01590    {
01591       if(!group)
01592       {
01593          context->idxstack->pushed = 0;
01594          context->idxstack->pulled = 0;
01595       }
01596       wkc = 1;
01597       /* LRW blocked by one or more slaves ? */
01598       if (context->grouplist[group].blockLRW)
01599       {
01600          /* if inputs available generate LRD */
01601          if(context->grouplist[group].Ibytes)
01602          {
01603             currentsegment = context->grouplist[group].Isegment;
01604             data = context->grouplist[group].inputs;
01605             length = context->grouplist[group].Ibytes;
01606             LogAdr += context->grouplist[group].Obytes;
01607             /* segment transfer if needed */
01608             do
01609             {
01610                if(currentsegment == context->grouplist[group].Isegment)
01611                {
01612                   sublength = context->grouplist[group].IOsegment[currentsegment++] - context->grouplist[group].Ioffset;
01613                }
01614                else
01615                {
01616                   sublength = context->grouplist[group].IOsegment[currentsegment++];
01617                }
01618                /* get new index */
01619                idx = ecx_getindex(context->port);
01620                w1 = LO_WORD(LogAdr);
01621                w2 = HI_WORD(LogAdr);
01622                ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRD, idx, w1, w2, sublength, data);
01623                if(first)
01624                {
01625                   context->DCl = sublength;
01626                   /* FPRMW in second datagram */
01627                   context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
01628                                            context->slavelist[context->grouplist[group].DCnext].configadr,
01629                                            ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
01630                   first = FALSE;
01631                }
01632                /* send frame */
01633                ecx_outframe_red(context->port, idx);
01634                /* push index and data pointer on stack */
01635                ecx_pushindex(context, idx, data, sublength);
01636                length -= sublength;
01637                LogAdr += sublength;
01638                data += sublength;
01639             } while (length && (currentsegment < context->grouplist[group].nsegments));
01640          }
01641          /* if outputs available generate LWR */
01642          if(context->grouplist[group].Obytes)
01643          {
01644             data = context->grouplist[group].outputs;
01645             length = context->grouplist[group].Obytes;
01646             LogAdr = context->grouplist[group].logstartaddr;
01647             currentsegment = 0;
01648             /* segment transfer if needed */
01649             do
01650             {
01651                sublength = context->grouplist[group].IOsegment[currentsegment++];
01652                if((length - sublength) < 0)
01653                {
01654                   sublength = length;
01655                }
01656                /* get new index */
01657                idx = ecx_getindex(context->port);
01658                w1 = LO_WORD(LogAdr);
01659                w2 = HI_WORD(LogAdr);
01660                ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LWR, idx, w1, w2, sublength, data);
01661                if(first)
01662                {
01663                   context->DCl = sublength;
01664                   /* FPRMW in second datagram */
01665                   context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
01666                                            context->slavelist[context->grouplist[group].DCnext].configadr,
01667                                            ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
01668                   first = FALSE;
01669                }
01670                /* send frame */
01671                ecx_outframe_red(context->port, idx);
01672                /* push index and data pointer on stack */
01673                ecx_pushindex(context, idx, data, sublength);
01674                length -= sublength;
01675                LogAdr += sublength;
01676                data += sublength;
01677             } while (length && (currentsegment < context->grouplist[group].nsegments));
01678          }
01679       }
01680       /* LRW can be used */
01681       else
01682       {
01683          if (context->grouplist[group].Obytes)
01684          {
01685             data = context->grouplist[group].outputs;
01686          }
01687          else
01688          {
01689             data = context->grouplist[group].inputs;
01690          }
01691          /* segment transfer if needed */
01692          do
01693          {
01694             sublength = context->grouplist[group].IOsegment[currentsegment++];
01695             /* get new index */
01696             idx = ecx_getindex(context->port);
01697             w1 = LO_WORD(LogAdr);
01698             w2 = HI_WORD(LogAdr);
01699             ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRW, idx, w1, w2, sublength, data);
01700             if(first)
01701             {
01702                context->DCl = sublength;
01703                /* FPRMW in second datagram */
01704                context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
01705                                         context->slavelist[context->grouplist[group].DCnext].configadr,
01706                                         ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
01707                first = FALSE;
01708             }
01709             /* send frame */
01710             ecx_outframe_red(context->port, idx);
01711             /* push index and data pointer on stack */
01712             ecx_pushindex(context, idx, data, sublength);
01713             length -= sublength;
01714             LogAdr += sublength;
01715             data += sublength;
01716          } while (length && (currentsegment < context->grouplist[group].nsegments));
01717       }
01718    }
01719 
01720    return wkc;
01721 }
01722 
01732 int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeout)
01733 {
01734    int pos, idx;
01735    int wkc = 0, wkc2;
01736    uint16 le_wkc = 0;
01737    int64 le_DCtime;
01738    boolean first = FALSE;
01739 
01740    if(context->grouplist[group].hasdc)
01741    {
01742       first = TRUE;
01743    }
01744    /* get first index */
01745    pos = ecx_pullindex(context);
01746    /* read the same number of frames as send */
01747    while (pos >= 0)
01748    {
01749       idx = context->idxstack->idx[pos];
01750       wkc2 = ecx_waitinframe(context->port, context->idxstack->idx[pos], timeout);
01751       /* check if there is input data in frame */
01752       if (wkc2 > EC_NOFRAME)
01753       {
01754          if((context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRD) || (context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRW))
01755          {
01756             if(first)
01757             {
01758                memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->DCl);
01759                memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
01760                wkc = etohs(le_wkc);
01761                memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
01762                *(context->DCtime) = etohll(le_DCtime);
01763                first = FALSE;
01764             }
01765             else
01766             {
01767                /* copy input data back to process data buffer */
01768                memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->idxstack->length[pos]);
01769                wkc += wkc2;
01770             }
01771          }
01772          else if(context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LWR)
01773          {
01774             if(first)
01775             {
01776                memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
01777                /* output WKC counts 2 times when using LRW, emulate the same for LWR */
01778                wkc = etohs(le_wkc) * 2;
01779                memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
01780                *(context->DCtime) = etohll(le_DCtime);
01781                first = FALSE;
01782             }
01783             else
01784             {
01785                /* output WKC counts 2 times when using LRW, emulate the same for LWR */
01786                wkc += wkc2 * 2;
01787             }
01788          }
01789       }
01790       /* release buffer */
01791       ecx_setbufstat(context->port, idx, EC_BUF_EMPTY);
01792       /* get next index */
01793       pos = ecx_pullindex(context);
01794    }
01795 
01796    return wkc;
01797 }
01798 
01799 
01800 int ecx_send_processdata(ecx_contextt *context)
01801 {
01802    return ecx_send_processdata_group(context, 0);
01803 }
01804 
01805 int ecx_receive_processdata(ecx_contextt *context, int timeout)
01806 {
01807    return ecx_receive_processdata_group(context, 0, timeout);
01808 }
01809 
01810 #ifdef EC_VER1
01811 void ec_pusherror(const ec_errort *Ec)
01812 {
01813    ecx_pusherror(&ecx_context, Ec);
01814 }
01815 
01816 boolean ec_poperror(ec_errort *Ec)
01817 {
01818    return ecx_poperror(&ecx_context, Ec);
01819 }
01820 
01821 boolean ec_iserror(void)
01822 {
01823    return ecx_iserror(&ecx_context);
01824 }
01825 
01826 void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
01827 {
01828    ecx_packeterror(&ecx_context, Slave, Index, SubIdx, ErrorCode);
01829 }
01830 
01831 static void ec_mbxerror(uint16 Slave,uint16 Detail)
01832 {
01833    ecx_mbxerror (&ecx_context, Slave, Detail);
01834 }
01835 
01836 static void ec_mbxemergencyerror(uint16 Slave,uint16 ErrorCode,uint16 ErrorReg,
01837     uint8 b1, uint16 w1, uint16 w2)
01838 {
01839    ecx_mbxemergencyerror (&ecx_context, Slave, ErrorCode, ErrorReg, b1, w1, w2);
01840 }
01841 
01842 int ec_init(char * ifname)
01843 {
01844    return ecx_init(&ecx_context, ifname);
01845 }
01846 
01847 int ec_init_redundant(char *ifname, char *if2name)
01848 {
01849    return ecx_init_redundant (&ecx_context, &ecx_redport, ifname, if2name);
01850 }
01851 
01852 void ec_close(void)
01853 {
01854    ecx_close(&ecx_context);
01855 };
01856 
01857 uint8 ec_siigetbyte(uint16 slave, uint16 address)
01858 {
01859    return ecx_siigetbyte (&ecx_context, slave, address);
01860 }
01861 
01862 int16 ec_siifind(uint16 slave, uint16 cat)
01863 {
01864    return ecx_siifind (&ecx_context, slave, cat);
01865 }
01866 
01867 void ec_siistring(char *str, uint16 slave, uint16 Sn)
01868 {
01869    ecx_siistring(&ecx_context, str, slave, Sn);
01870 }
01871 
01872 uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU)
01873 {
01874    return ecx_siiFMMU (&ecx_context, slave, FMMU);
01875 }
01876 
01877 uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM)
01878 {
01879    return ecx_siiSM (&ecx_context, slave, SM);
01880 }
01881 
01882 uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n)
01883 {
01884    return ecx_siiSMnext (&ecx_context, slave, SM, n);
01885 }
01886 
01887 int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t)
01888 {
01889    return ecx_siiPDO (&ecx_context, slave, PDO, t);
01890 }
01891 
01892 int ec_readstate(void)
01893 {
01894    return ecx_readstate (&ecx_context);
01895 }
01896 
01897 int ec_writestate(uint16 slave)
01898 {
01899    return ecx_writestate(&ecx_context, slave);
01900 }
01901 
01902 uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout)
01903 {
01904    return ecx_statecheck (&ecx_context, slave, reqstate, timeout);
01905 }
01906 
01907 int ec_mbxempty(uint16 slave, int timeout)
01908 {
01909    return ecx_mbxempty (&ecx_context, slave, timeout);
01910 }
01911 
01912 int ec_mbxsend(uint16 slave,ec_mbxbuft *mbx, int timeout)
01913 {
01914    return ecx_mbxsend (&ecx_context, slave, mbx, timeout);
01915 }
01916 
01917 int ec_mbxreceive(uint16 slave, ec_mbxbuft *mbx, int timeout)
01918 {
01919    return ecx_mbxreceive (&ecx_context, slave, mbx, timeout);
01920 }
01921 
01922 void ec_esidump(uint16 slave, uint8 *esibuf)
01923 {
01924    ecx_esidump (&ecx_context, slave, esibuf);
01925 }
01926 
01927 uint32 ec_readeeprom(uint16 slave, uint16 eeproma, int timeout)
01928 {
01929    return ecx_readeeprom (&ecx_context, slave, eeproma, timeout);
01930 }
01931 
01932 int ec_writeeeprom(uint16 slave, uint16 eeproma, uint16 data, int timeout)
01933 {
01934    return ecx_writeeeprom (&ecx_context, slave, eeproma, data, timeout);
01935 }
01936 
01937 int ec_eeprom2master(uint16 slave)
01938 {
01939    return ecx_eeprom2master(&ecx_context, slave);
01940 }
01941 
01942 int ec_eeprom2pdi(uint16 slave)
01943 {
01944    return ecx_eeprom2pdi(&ecx_context, slave);
01945 }
01946 
01947 uint16 ec_eeprom_waitnotbusyAP(uint16 aiadr,uint16 *estat, int timeout)
01948 {
01949    return ecx_eeprom_waitnotbusyAP (&ecx_context, aiadr, estat, timeout);
01950 }
01951 
01952 uint64 ec_readeepromAP(uint16 aiadr, uint16 eeproma, int timeout)
01953 {
01954    return ecx_readeepromAP (&ecx_context, aiadr, eeproma, timeout);
01955 }
01956 
01957 int ec_writeeepromAP(uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
01958 {
01959    return ecx_writeeepromAP (&ecx_context, aiadr, eeproma, data, timeout);
01960 }
01961 
01962 uint16 ec_eeprom_waitnotbusyFP(uint16 configadr,uint16 *estat, int timeout)
01963 {
01964    return ecx_eeprom_waitnotbusyFP (&ecx_context, configadr, estat, timeout);
01965 }
01966 
01967 uint64 ec_readeepromFP(uint16 configadr, uint16 eeproma, int timeout)
01968 {
01969    return ecx_readeepromFP (&ecx_context, configadr, eeproma, timeout);
01970 }
01971 
01972 int ec_writeeepromFP(uint16 configadr, uint16 eeproma, uint16 data, int timeout)
01973 {
01974    return ecx_writeeepromFP (&ecx_context, configadr, eeproma, data, timeout);
01975 }
01976 
01977 void ec_readeeprom1(uint16 slave, uint16 eeproma)
01978 {
01979    ecx_readeeprom1 (&ecx_context, slave, eeproma);
01980 }
01981 
01982 uint32 ec_readeeprom2(uint16 slave, int timeout)
01983 {
01984    return ecx_readeeprom2 (&ecx_context, slave, timeout);
01985 }
01986 
01987 int ec_send_processdata_group(uint8 group)
01988 {
01989    return ecx_send_processdata_group (&ecx_context, group);
01990 }
01991 
01992 int ec_receive_processdata_group(uint8 group, int timeout)
01993 {
01994    return ecx_receive_processdata_group (&ecx_context, group, timeout);
01995 }
01996 
01997 int ec_send_processdata(void)
01998 {
01999    return ec_send_processdata_group(0);
02000 }
02001 
02002 int ec_receive_processdata(int timeout)
02003 {
02004    return ec_receive_processdata_group(0, timeout);
02005 }
02006 #endif


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