ethercatconfig.c
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : ethercatconfig.c
00005  * Version : 1.2.5
00006  * Date    : 09-04-2011
00007  * Copyright (C) 2005-2011 Speciaal Machinefabriek Ketels v.o.f.
00008  * Copyright (C) 2005-2011 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 
00049 #include <stdio.h>
00050 #include <string.h>
00051 #include <sys/time.h>
00052 #include <unistd.h>
00053 #include <youbot_driver/soem/ethercattype.h>
00054 #include <youbot_driver/soem/nicdrv.h>
00055 #include <youbot_driver/soem/ethercatbase.h>
00056 #include <youbot_driver/soem/ethercatmain.h>
00057 #include <youbot_driver/soem/ethercatcoe.h>
00058 #include <youbot_driver/soem/ethercatsoe.h>
00059 #include <youbot_driver/soem/ethercatconfig.h>
00060 
00061 // define if debug printf is needed
00062 //#define EC_DEBUG
00063 
00064 #ifdef EC_DEBUG
00065 #define EC_PRINT printf
00066 #else
00067 #define EC_PRINT(...) do {} while (0)
00068 #endif
00069 
00071 typedef const struct
00072 {
00074   uint32 man;
00076   uint32 id;
00078   char name[EC_MAXNAME + 1];
00080   uint8 Dtype;
00082   uint16 Ibits;
00084   uint16 Obits;
00086   uint16 SM2a;
00088   uint32 SM2f;
00090   uint16 SM3a;
00092   uint32 SM3f;
00094   uint8 FM0ac;
00096   uint8 FM1ac;
00097 } ec_configlist_t;
00098 
00099 #include <youbot_driver/soem/ethercatconfiglist.h>
00100 
00102 #define EC_DEFAULTMBXSM0        0x00010026
00103 
00104 #define EC_DEFAULTMBXSM1        0x00010022
00105 
00106 #define EC_DEFAULTDOSM0         0x00010044
00107 
00109 static ec_eepromSMt ec_SM;
00111 static ec_eepromFMMUt ec_FMMU;
00112 
00119 int ec_findconfig(uint32 man, uint32 id)
00120 {
00121   int i = 0;
00122 
00123   do
00124   {
00125     i++;
00126   } while ((ec_configlist[i].man != EC_CONFIGEND) && ((ec_configlist[i].man != man) || (ec_configlist[i].id != id)));
00127   if (ec_configlist[i].man == EC_CONFIGEND)
00128     i = 0;
00129 
00130   return i;
00131 }
00132 
00138 int ec_config_init(uint8 usetable)
00139 {
00140   uint16 w, slave, ADPh, configadr, /*mbx_wo, mbx_ro, mbx_l, mbx_rl,*/ssigen;
00141   uint16 topology, estat;
00142   int16 topoc, slavec;
00143   uint8 b, h;
00144   uint8 zbuf[64];
00145   uint8 SMc;
00146   uint32 eedat;
00147   int wkc, cindex, nSM, lp;
00148 
00149   EC_PRINT("ec_config_init %d\n", usetable);
00150   ec_slavecount = 0;
00151   /* clean ec_slave array */
00152   memset(&ec_slave, 0x00, sizeof(ec_slave));
00153   memset(&zbuf, 0x00, sizeof(zbuf));
00154   memset(&ec_group, 0x00, sizeof(ec_group));
00155   for (lp = 0; lp < EC_MAXGROUP; lp++)
00156   {
00157     ec_group[lp].logstartaddr = lp << 16; /* default start address per group entry */
00158   }
00159   w = 0x0000;
00160   wkc = ec_BRD(0x0000, ECT_REG_TYPE, sizeof(w), &w, EC_TIMEOUTSAFE); /* detect number of slaves */
00161   if (wkc > 0)
00162   {
00163     ec_slavecount = wkc;
00164     b = 0x00;
00165     ec_BWR(0x0000, ECT_REG_DLPORT, sizeof(b), &b, EC_TIMEOUTRET); /* deact loop manual */
00166     w = htoes(0x0004);
00167     ec_BWR(0x0000, ECT_REG_IRQMASK, sizeof(w), &w, EC_TIMEOUTRET); /* set IRQ mask */
00168     ec_BWR(0x0000, ECT_REG_RXERR, 8, &zbuf, EC_TIMEOUTRET); /* reset CRC counters */
00169     ec_BWR(0x0000, ECT_REG_FMMU0, 16 * 3, &zbuf, EC_TIMEOUTRET); /* reset FMMU's */
00170     ec_BWR(0x0000, ECT_REG_SM0, 8 * 4, &zbuf, EC_TIMEOUTRET); /* reset SyncM */
00171     ec_BWR(0x0000, ECT_REG_DCSYSTIME, 4, &zbuf, EC_TIMEOUTRET); /* reset system time+ofs */
00172     w = htoes(0x1000);
00173     ec_BWR(0x0000, ECT_REG_DCSPEEDCNT, sizeof(w), &w, EC_TIMEOUTRET); /* DC speedstart */
00174     w = htoes(0x0c00);
00175     ec_BWR(0x0000, ECT_REG_DCTIMEFILT, sizeof(w), &w, EC_TIMEOUTRET); /* DC filt expr */
00176     b = 0x00;
00177     ec_BWR(0x0000, ECT_REG_DLALIAS, sizeof(b), &b, EC_TIMEOUTRET); /* Ignore Alias register */
00178     b = EC_STATE_INIT | EC_STATE_ACK;
00179     ec_BWR(0x0000, ECT_REG_ALCTL, sizeof(b), &b, EC_TIMEOUTRET); /* Reset all slaves to Init */
00180     b = 2;
00181     ec_BWR(0x0000, ECT_REG_EEPCFG, sizeof(b), &b, EC_TIMEOUTRET); /* force Eeprom from PDI */
00182     b = 0;
00183     ec_BWR(0x0000, ECT_REG_EEPCFG, sizeof(b), &b, EC_TIMEOUTRET); /* set Eeprom to master */
00184 
00185     for (slave = 1; slave <= ec_slavecount; slave++)
00186     {
00187       ADPh = (uint16)(1 - slave);
00188       ec_slave[slave].Itype = etohs(ec_APRDw(ADPh, ECT_REG_PDICTL, EC_TIMEOUTRET)); /* read interface type of slave */
00189       /* a node offset is used to improve readibility of network frames */
00190       /* this has no impact on the number of addressable slaves (auto wrap around) */
00191       ec_APWRw(ADPh, ECT_REG_STADR, htoes(slave + EC_NODEOFFSET), EC_TIMEOUTRET); /* set node address of slave */
00192       if (slave == 1)
00193         b = 1; /* kill non ecat frames for first slave */
00194       else
00195         b = 0; /* pass all frames for following slaves */
00196       ec_APWRw(ADPh, ECT_REG_DLCTL, htoes(b), EC_TIMEOUTRET); /* set non ecat frame behaviour */
00197       configadr = etohs(ec_APRDw(ADPh, ECT_REG_STADR, EC_TIMEOUTRET));
00198       ec_slave[slave].configadr = configadr;
00199       ec_FPRD(configadr, ECT_REG_ALIAS, sizeof(ec_slave[slave].aliasadr), &ec_slave[slave].aliasadr, EC_TIMEOUTRET);
00200       ec_FPRD(configadr, ECT_REG_EEPSTAT, sizeof(estat), &estat, EC_TIMEOUTRET);
00201       estat = etohs(estat);
00202       if (estat & EC_ESTAT_R64) /* check if slave can read 8 byte chunks */
00203         ec_slave[slave].eep_8byte = 1;
00204       ec_readeeprom1(slave, ECT_SII_MANUF); /* Manuf */
00205     }
00206     for (slave = 1; slave <= ec_slavecount; slave++)
00207     {
00208       ec_slave[slave].eep_man = etohl(ec_readeeprom2(slave, EC_TIMEOUTEEP)); /* Manuf */
00209       ec_readeeprom1(slave, ECT_SII_ID); /* ID */
00210     }
00211     for (slave = 1; slave <= ec_slavecount; slave++)
00212     {
00213       ec_slave[slave].eep_id = etohl(ec_readeeprom2(slave, EC_TIMEOUTEEP)); /* ID */
00214       ec_readeeprom1(slave, ECT_SII_REV); /* revision */
00215     }
00216     for (slave = 1; slave <= ec_slavecount; slave++)
00217     {
00218       ec_slave[slave].eep_rev = etohl(ec_readeeprom2(slave, EC_TIMEOUTEEP)); /* revision */
00219       ec_readeeprom1(slave, ECT_SII_RXMBXADR); /* write mailbox address + mailboxsize */
00220     }
00221     for (slave = 1; slave <= ec_slavecount; slave++)
00222     {
00223       eedat = etohl(ec_readeeprom2(slave, EC_TIMEOUTEEP)); /* write mailbox address and mailboxsize */
00224       ec_slave[slave].mbx_wo = (uint16)LO_WORD(eedat);
00225       ec_slave[slave].mbx_l = (uint16)HI_WORD(eedat);
00226       if (ec_slave[slave].mbx_l > 0)
00227         ec_readeeprom1(slave, ECT_SII_TXMBXADR); /* read mailbox offset */
00228     }
00229     for (slave = 1; slave <= ec_slavecount; slave++)
00230     {
00231       if (ec_slave[slave].mbx_l > 0)
00232       {
00233         eedat = etohl(ec_readeeprom2(slave, EC_TIMEOUTEEP)); /* read mailbox offset */
00234         ec_slave[slave].mbx_ro = (uint16)LO_WORD(eedat); /* read mailbox offset */
00235         ec_slave[slave].mbx_rl = (uint16)HI_WORD(eedat); /*read mailbox length */
00236         if (ec_slave[slave].mbx_rl == 0)
00237           ec_slave[slave].mbx_rl = ec_slave[slave].mbx_l;
00238       }
00239       configadr = ec_slave[slave].configadr;
00240       /*mbx_ro = ec_slave[slave].mbx_ro;
00241        mbx_wo = ec_slave[slave].mbx_wo;
00242        mbx_l = ec_slave[slave].mbx_l;
00243        mbx_rl = ec_slave[slave].mbx_rl;*/
00244       if ((etohs(ec_FPRDw(configadr, ECT_REG_ESCSUP, EC_TIMEOUTRET)) & 0x04) > 0) /* Support DC? */
00245         ec_slave[slave].hasdc = TRUE;
00246       else
00247         ec_slave[slave].hasdc = FALSE;
00248       topology = etohs(ec_FPRDw(configadr, ECT_REG_DLSTAT, EC_TIMEOUTRET)); /* extract topology from DL status */
00249       h = 0;
00250       b = 0;
00251       if ((topology & 0x0300) == 0x0200) /* port0 open and communication established */
00252       {
00253         h++;
00254         b |= 0x01;
00255       }
00256       if ((topology & 0x0c00) == 0x0800) /* port1 open and communication established */
00257       {
00258         h++;
00259         b |= 0x02;
00260       }
00261       if ((topology & 0x3000) == 0x2000) /* port2 open and communication established */
00262       {
00263         h++;
00264         b |= 0x04;
00265       }
00266       if ((topology & 0xc000) == 0x8000) /* port3 open and communication established */
00267       {
00268         h++;
00269         b |= 0x08;
00270       }
00271       /* ptype = Physical type*/
00272       ec_slave[slave].ptype = LO_BYTE(etohs(ec_FPRDw(configadr, ECT_REG_PORTDES, EC_TIMEOUTRET)));
00273       ec_slave[slave].topology = h;
00274       ec_slave[slave].activeports = b;
00275       /* 0=no links, not possible             */
00276       /* 1=1 link  , end of line              */
00277       /* 2=2 links , one before and one after */
00278       /* 3=3 links , split point              */
00279       /* 4=4 links , cross point              */
00280       /* search for parent */
00281       ec_slave[slave].parent = 0; /* parent is master */
00282       if (slave > 1)
00283       {
00284         topoc = 0;
00285         slavec = slave - 1;
00286         do
00287         {
00288           topology = ec_slave[slavec].topology;
00289           if (topology == 1)
00290             topoc--; /* endpoint found */
00291           if (topology == 3)
00292             topoc++; /* split found */
00293           if (topology == 4)
00294             topoc += 2; /* cross found */
00295           if (((topoc >= 0) && (topology > 1)) || (slavec == 1)) /* parent found */
00296           {
00297             ec_slave[slave].parent = slavec;
00298             slavec = 1;
00299           }
00300           slavec--;
00301         } while (slavec > 0);
00302       }
00303 
00304       w = ec_statecheck(slave, EC_STATE_INIT, EC_TIMEOUTSTATE); //* check state change Init */
00305 
00306       /* set default mailbox configuration if slave has mailbox */
00307       if (ec_slave[slave].mbx_l > 0)
00308       {
00309         ec_slave[slave].SMtype[0] = 1;
00310         ec_slave[slave].SMtype[1] = 2;
00311         ec_slave[slave].SMtype[2] = 3;
00312         ec_slave[slave].SMtype[3] = 4;
00313         ec_slave[slave].SM[0].StartAddr = htoes(ec_slave[slave].mbx_wo);
00314         ec_slave[slave].SM[0].SMlength = htoes(ec_slave[slave].mbx_l);
00315         ec_slave[slave].SM[0].SMflags = htoel(EC_DEFAULTMBXSM0);
00316         ec_slave[slave].SM[1].StartAddr = htoes(ec_slave[slave].mbx_ro);
00317         ec_slave[slave].SM[1].SMlength = htoes(ec_slave[slave].mbx_rl);
00318         ec_slave[slave].SM[1].SMflags = htoel(EC_DEFAULTMBXSM1);
00319         ec_slave[slave].mbx_proto = ec_readeeprom(slave, ECT_SII_MBXPROTO, EC_TIMEOUTEEP);
00320       }
00321       cindex = 0;
00322       /* use configuration table ? */
00323       if (usetable)
00324       {
00325         cindex = ec_findconfig(ec_slave[slave].eep_man, ec_slave[slave].eep_id);
00326         ec_slave[slave].configindex = cindex;
00327       }
00328       /* slave found in configuration table ? */
00329       if (cindex)
00330       {
00331         ec_slave[slave].Dtype = ec_configlist[cindex].Dtype;
00332         strcpy(ec_slave[slave].name, ec_configlist[cindex].name);
00333         ec_slave[slave].Ibits = ec_configlist[cindex].Ibits;
00334         ec_slave[slave].Obits = ec_configlist[cindex].Obits;
00335         if (ec_slave[slave].Obits)
00336           ec_slave[slave].FMMU0func = 1;
00337         if (ec_slave[slave].Ibits)
00338           ec_slave[slave].FMMU1func = 2;
00339         ec_slave[slave].FMMU[0].FMMUactive = ec_configlist[cindex].FM0ac;
00340         ec_slave[slave].FMMU[1].FMMUactive = ec_configlist[cindex].FM1ac;
00341         ec_slave[slave].SM[2].StartAddr = htoes(ec_configlist[cindex].SM2a);
00342         ec_slave[slave].SM[2].SMflags = htoel(ec_configlist[cindex].SM2f);
00343         /* simple (no mailbox) output slave found ? */
00344         if (ec_slave[slave].Obits && !ec_slave[slave].SM[2].StartAddr)
00345         {
00346           ec_slave[slave].SM[0].StartAddr = htoes(0x0f00);
00347           ec_slave[slave].SM[0].SMlength = htoes((ec_slave[slave].Obits + 7) / 8);
00348           ec_slave[slave].SM[0].SMflags = htoel(EC_DEFAULTDOSM0);
00349           ec_slave[slave].FMMU[0].FMMUactive = 1;
00350           ec_slave[slave].FMMU[0].FMMUtype = 2;
00351           ec_slave[slave].SMtype[0] = 3;
00352         }
00353         /* complex output slave */
00354         else
00355         {
00356           ec_slave[slave].SM[2].SMlength = htoes((ec_slave[slave].Obits + 7) / 8);
00357           ec_slave[slave].SMtype[2] = 3;
00358         }
00359         ec_slave[slave].SM[3].StartAddr = htoes(ec_configlist[cindex].SM3a);
00360         ec_slave[slave].SM[3].SMflags = htoel(ec_configlist[cindex].SM3f);
00361         /* simple (no mailbox) input slave found ? */
00362         if (ec_slave[slave].Ibits && !ec_slave[slave].SM[3].StartAddr)
00363         {
00364           ec_slave[slave].SM[1].StartAddr = htoes(0x1000);
00365           ec_slave[slave].SM[1].SMlength = htoes((ec_slave[slave].Ibits + 7) / 8);
00366           ec_slave[slave].SM[1].SMflags = htoel(0x00000000);
00367           ec_slave[slave].FMMU[1].FMMUactive = 1;
00368           ec_slave[slave].FMMU[1].FMMUtype = 1;
00369           ec_slave[slave].SMtype[1] = 4;
00370         }
00371         /* complex input slave */
00372         else
00373         {
00374           ec_slave[slave].SM[3].SMlength = htoes((ec_slave[slave].Ibits + 7) / 8);
00375           ec_slave[slave].SMtype[3] = 4;
00376         }
00377       }
00378       /* slave not in configuration table, find out via SII */
00379       else
00380       {
00381         ssigen = ec_siifind(slave, ECT_SII_GENERAL);
00382         /* SII general section */
00383         if (ssigen)
00384         {
00385           ec_slave[slave].CoEdetails = ec_siigetbyte(slave, ssigen + 0x07);
00386           ec_slave[slave].FoEdetails = ec_siigetbyte(slave, ssigen + 0x08);
00387           ec_slave[slave].EoEdetails = ec_siigetbyte(slave, ssigen + 0x09);
00388           ec_slave[slave].SoEdetails = ec_siigetbyte(slave, ssigen + 0x0a);
00389           if ((ec_siigetbyte(slave, ssigen + 0x0d) & 0x02) > 0)
00390           {
00391             ec_slave[slave].blockLRW = 1;
00392             ec_slave[0].blockLRW++;
00393           }
00394           ec_slave[slave].Ebuscurrent = ec_siigetbyte(slave, ssigen + 0x0e);
00395           ec_slave[slave].Ebuscurrent += ec_siigetbyte(slave, ssigen + 0x0f) << 8;
00396           ec_slave[0].Ebuscurrent += ec_slave[slave].Ebuscurrent;
00397         }
00398         /* SII strings section */
00399         if (ec_siifind(slave, ECT_SII_STRING) > 0)
00400           ec_siistring(ec_slave[slave].name, slave, 1);
00401         /* no name for slave found, use constructed name */
00402         else
00403         {
00404           sprintf(ec_slave[slave].name, "? M:%8.8x I:%8.8x", (unsigned int)ec_slave[slave].eep_man,
00405                   (unsigned int)ec_slave[slave].eep_id);
00406         }
00407         /* SII SM section */
00408         nSM = ec_siiSM(slave, &ec_SM);
00409         if (nSM > 0)
00410         {
00411           ec_slave[slave].SM[0].StartAddr = htoes(ec_SM.PhStart);
00412           ec_slave[slave].SM[0].SMlength = htoes(ec_SM.Plength);
00413           ec_slave[slave].SM[0].SMflags = htoel((ec_SM.Creg) + (ec_SM.Activate << 16));
00414           SMc = 1;
00415           while ((SMc < EC_MAXSM) && ec_siiSMnext(slave, &ec_SM, SMc))
00416           {
00417             ec_slave[slave].SM[SMc].StartAddr = htoes(ec_SM.PhStart);
00418             ec_slave[slave].SM[SMc].SMlength = htoes(ec_SM.Plength);
00419             ec_slave[slave].SM[SMc].SMflags = htoel((ec_SM.Creg) + (ec_SM.Activate << 16));
00420             SMc++;
00421           }
00422         }
00423         /* SII FMMU section */
00424         if (ec_siiFMMU(slave, &ec_FMMU))
00425         {
00426           if (ec_FMMU.FMMU0 != 0xff)
00427             ec_slave[slave].FMMU0func = ec_FMMU.FMMU0;
00428           if (ec_FMMU.FMMU1 != 0xff)
00429             ec_slave[slave].FMMU1func = ec_FMMU.FMMU1;
00430           if (ec_FMMU.FMMU2 != 0xff)
00431             ec_slave[slave].FMMU2func = ec_FMMU.FMMU2;
00432           if (ec_FMMU.FMMU3 != 0xff)
00433             ec_slave[slave].FMMU3func = ec_FMMU.FMMU3;
00434         }
00435       }
00436 
00437       if (ec_slave[slave].mbx_l > 0)
00438       {
00439         if (ec_slave[slave].SM[0].StartAddr == 0x0000) /* should never happen */
00440         {
00441           ec_slave[slave].SM[0].StartAddr = htoes(0x1000);
00442           ec_slave[slave].SM[0].SMlength = htoes(0x0080);
00443           ec_slave[slave].SM[0].SMflags = htoel(EC_DEFAULTMBXSM0);
00444           ec_slave[slave].SMtype[0] = 1;
00445         }
00446         if (ec_slave[slave].SM[1].StartAddr == 0x0000) /* should never happen */
00447         {
00448           ec_slave[slave].SM[1].StartAddr = htoes(0x1080);
00449           ec_slave[slave].SM[1].SMlength = htoes(0x0080);
00450           ec_slave[slave].SM[1].SMflags = htoel(EC_DEFAULTMBXSM1);
00451           ec_slave[slave].SMtype[1] = 2;
00452         }
00453         /* program SM0 mailbox in for slave */
00454         ec_FPWR(configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
00455         /* program SM1 mailbox out for slave */
00456         // usleep(1000); // was needed for NETX (needs internal time after SM update)
00457         ec_FPWR(configadr, ECT_REG_SM1, sizeof(ec_smt), &ec_slave[slave].SM[1], EC_TIMEOUTRET);
00458       }
00459       ec_FPWRw(configadr, ECT_REG_ALCTL, htoes(EC_STATE_PRE_OP | EC_STATE_ACK), EC_TIMEOUTRET); /* set preop status */
00460     }
00461   }
00462   return wkc;
00463 }
00464 
00471 int ec_config_map_group(void *pIOmap, uint8 group)
00472 {
00473   uint16 slave, configadr;
00474   int Isize, Osize, BitCount, ByteCount, FMMUsize, FMMUdone;
00475   uint16 SMlength;
00476   uint8 BitPos, EndAddr;
00477   uint8 SMc, FMMUc;
00478   uint32 LogAddr = 0;
00479   uint32 oLogAddr = 0;
00480   uint32 diff;
00481   int nSM; //, rval;
00482   ec_eepromPDOt eepPDO;
00483   uint16 currentsegment = 0;
00484   uint32 segmentsize = 0;
00485 
00486   if ((ec_slavecount > 0) && (group < EC_MAXGROUP))
00487   {
00488     EC_PRINT("ec_config_map_group IOmap:%p group:%d\n", pIOmap, group);
00489     LogAddr = ec_group[group].logstartaddr;
00490     oLogAddr = LogAddr;
00491     BitPos = 0;
00492     ec_group[group].nsegments = 0;
00493     ec_group[group].expectedWKC = 0;
00494 
00495     /* find output mapping of slave and program FMMU */
00496     for (slave = 1; slave <= ec_slavecount; slave++)
00497     {
00498       configadr = ec_slave[slave].configadr;
00499 
00500       ec_statecheck(slave, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); /* check state change pre-op */
00501 
00502       EC_PRINT(" >Slave %d, configadr %x, state %2.2x\n", slave, ec_slave[slave].configadr, ec_slave[slave].state);
00503 
00504       if (!group || (group == ec_slave[slave].group))
00505       {
00506 
00507         /* if slave not found in configlist find IO mapping in slave self */
00508         if (!ec_slave[slave].configindex)
00509         {
00510           Isize = 0;
00511           Osize = 0;
00512           if (ec_slave[slave].mbx_proto & ECT_MBXPROT_COE) /* has CoE */
00513           {
00514             if (ec_slave[slave].CoEdetails & ECT_COEDET_SDOCA) /* has Complete Access */
00515               /* read PDO mapping via CoE and use Complete Access */
00516               /*rval =*/ec_readPDOmapCA(slave, &Osize, &Isize);
00517             else
00518               /* read PDO mapping via CoE */
00519               /*rval =*/ec_readPDOmap(slave, &Osize, &Isize);
00520             EC_PRINT("  CoE Osize:%d Isize:%d\n", Osize, Isize);
00521           }
00522           if ((!Isize && !Osize) && (ec_slave[slave].mbx_proto & ECT_MBXPROT_SOE)) /* has SoE */
00523           {
00524             /* read AT / MDT mapping via SoE */
00525             /*rval =*/ec_readIDNmap(slave, &Osize, &Isize);
00526             ec_slave[slave].SM[2].SMlength = htoes((Osize + 7) / 8);
00527             ec_slave[slave].SM[3].SMlength = htoes((Isize + 7) / 8);
00528             EC_PRINT("  SoE Osize:%d Isize:%d\n", Osize, Isize);
00529           }
00530           if (!Isize && !Osize) /* find PDO mapping by SII */
00531           {
00532             memset(&eepPDO, 0, sizeof(eepPDO));
00533             Isize = (int)ec_siiPDO(slave, &eepPDO, 0);
00534             EC_PRINT("  SII Isize:%d\n", Isize);
00535             for (nSM = 0; nSM < EC_MAXSM; nSM++)
00536             {
00537               if (eepPDO.SMbitsize[nSM] > 0)
00538               {
00539                 ec_slave[slave].SM[nSM].SMlength = htoes((eepPDO.SMbitsize[nSM] + 7) / 8);
00540                 ec_slave[slave].SMtype[nSM] = 4;
00541                 EC_PRINT("    SM%d length %d\n", nSM, eepPDO.SMbitsize[nSM]);
00542               }
00543             }
00544             Osize = (int)ec_siiPDO(slave, &eepPDO, 1);
00545             EC_PRINT("  SII Osize:%d\n", Osize);
00546             for (nSM = 0; nSM < EC_MAXSM; nSM++)
00547             {
00548               if (eepPDO.SMbitsize[nSM] > 0)
00549               {
00550                 ec_slave[slave].SM[nSM].SMlength = htoes((eepPDO.SMbitsize[nSM] + 7) / 8);
00551                 ec_slave[slave].SMtype[nSM] = 3;
00552                 EC_PRINT("    SM%d length %d\n", nSM, eepPDO.SMbitsize[nSM]);
00553               }
00554             }
00555           }
00556           ec_slave[slave].Obits = Osize;
00557           ec_slave[slave].Ibits = Isize;
00558           EC_PRINT("     ISIZE:%d %d OSIZE:%d\n", ec_slave[slave].Ibits, Isize, ec_slave[slave].Obits);
00559 
00560         }
00561 
00562         EC_PRINT("  SM programming\n");
00563         if (!ec_slave[slave].mbx_l && ec_slave[slave].SM[0].StartAddr)
00564         {
00565           ec_FPWR(configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
00566           EC_PRINT("    SM0 Type:%d StartAddr:%4.4x Flags:%8.8x\n", ec_slave[slave].SMtype[0],
00567                    ec_slave[slave].SM[0].StartAddr, ec_slave[slave].SM[0].SMflags);
00568         }
00569         if (!ec_slave[slave].mbx_l && ec_slave[slave].SM[1].StartAddr)
00570         {
00571           ec_FPWR(configadr, ECT_REG_SM1, sizeof(ec_smt), &ec_slave[slave].SM[1], EC_TIMEOUTRET);
00572           EC_PRINT("    SM1 Type:%d StartAddr:%4.4x Flags:%8.8x\n", ec_slave[slave].SMtype[1],
00573                    ec_slave[slave].SM[1].StartAddr, ec_slave[slave].SM[1].SMflags);
00574         }
00575         /* program SM2 to SMx */
00576         for (nSM = 2; nSM < EC_MAXSM; nSM++)
00577         {
00578           if (ec_slave[slave].SM[nSM].StartAddr)
00579           {
00580             /* check if SM length is zero -> clear enable flag */
00581             if (ec_slave[slave].SM[nSM].SMlength == 0)
00582               ec_slave[slave].SM[nSM].SMflags = htoel( etohl(ec_slave[slave].SM[nSM].SMflags) & EC_SMENABLEMASK);
00583             ec_FPWR(configadr, ECT_REG_SM0 + (nSM * sizeof(ec_smt)), sizeof(ec_smt), &ec_slave[slave].SM[nSM],
00584                     EC_TIMEOUTRET);
00585             EC_PRINT("    SM%d Type:%d StartAddr:%4.4x Flags:%8.8x\n", nSM, ec_slave[slave].SMtype[nSM],
00586                      ec_slave[slave].SM[nSM].StartAddr, ec_slave[slave].SM[nSM].SMflags);
00587           }
00588         }
00589         if (ec_slave[slave].Ibits > 7)
00590           ec_slave[slave].Ibytes = (ec_slave[slave].Ibits + 7) / 8;
00591         if (ec_slave[slave].Obits > 7)
00592           ec_slave[slave].Obytes = (ec_slave[slave].Obits + 7) / 8;
00593 
00594         FMMUc = ec_slave[slave].FMMUunused;
00595         SMc = 0;
00596         BitCount = 0;
00597         ByteCount = 0;
00598         EndAddr = 0;
00599         FMMUsize = 0;
00600         FMMUdone = 0;
00601         /* create output mapping */
00602         if (ec_slave[slave].Obits)
00603         {
00604           EC_PRINT("  OUTPUT MAPPING\n");
00605           /* search for SM that contribute to the output mapping */
00606           while ((SMc < (EC_MAXSM - 1)) && (FMMUdone < ((ec_slave[slave].Obits + 7) / 8)))
00607           {
00608             EC_PRINT("    FMMU %d\n", FMMUc);
00609             while ((SMc < (EC_MAXSM - 1)) && (ec_slave[slave].SMtype[SMc] != 3))
00610               SMc++;
00611             EC_PRINT("      SM%d\n", SMc);
00612             ec_slave[slave].FMMU[FMMUc].PhysStart = ec_slave[slave].SM[SMc].StartAddr;
00613             SMlength = etohs(ec_slave[slave].SM[SMc].SMlength);
00614             ByteCount += SMlength;
00615             BitCount += SMlength * 8;
00616             EndAddr = etohs(ec_slave[slave].SM[SMc].StartAddr)+ SMlength;
00617             while ((BitCount < ec_slave[slave].Obits) && (SMc < (EC_MAXSM - 1))) /* more SM for output */
00618             {
00619               SMc++;
00620               while ((SMc < (EC_MAXSM - 1)) && (ec_slave[slave].SMtype[SMc] != 3))
00621                 SMc++;
00622               /* if addresses from more SM connect use one FMMU otherwise break up in mutiple FMMU */
00623               if (etohs(ec_slave[slave].SM[SMc].StartAddr)> EndAddr ) break;
00624               EC_PRINT("      SM%d\n", SMc);
00625               SMlength = etohs(ec_slave[slave].SM[SMc].SMlength);
00626               ByteCount += SMlength;
00627               BitCount += SMlength * 8;
00628               EndAddr = etohs(ec_slave[slave].SM[SMc].StartAddr)+ SMlength;
00629             }
00630 
00631               /* bit oriented slave */
00632             if (!ec_slave[slave].Obytes)
00633             {
00634               ec_slave[slave].FMMU[FMMUc].LogStart = htoel(LogAddr);
00635               ec_slave[slave].FMMU[FMMUc].LogStartbit = BitPos;
00636               BitPos += ec_slave[slave].Obits - 1;
00637               if (BitPos > 7)
00638               {
00639                 LogAddr++;
00640                 BitPos -= 8;
00641               }
00642               FMMUsize = LogAddr - etohl(ec_slave[slave].FMMU[FMMUc].LogStart)+ 1;
00643               ec_slave[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
00644               ec_slave[slave].FMMU[FMMUc].LogEndbit = BitPos;
00645               BitPos++;
00646               if (BitPos > 7)
00647               {
00648                 LogAddr++;
00649                 BitPos -= 8;
00650               }
00651             }
00652             /* byte oriented slave */
00653             else
00654             {
00655               if (BitPos)
00656               {
00657                 LogAddr++;
00658                 BitPos = 0;
00659               }
00660               ec_slave[slave].FMMU[FMMUc].LogStart = htoel(LogAddr);
00661               ec_slave[slave].FMMU[FMMUc].LogStartbit = BitPos;
00662               BitPos = 7;
00663               FMMUsize = ByteCount;
00664               if ((FMMUsize + FMMUdone) > ec_slave[slave].Obytes)
00665                 FMMUsize = ec_slave[slave].Obytes - FMMUdone;
00666               LogAddr += FMMUsize;
00667               ec_slave[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
00668               ec_slave[slave].FMMU[FMMUc].LogEndbit = BitPos;
00669               BitPos = 0;
00670             }
00671             FMMUdone += FMMUsize;
00672             ec_slave[slave].FMMU[FMMUc].PhysStartBit = 0;
00673             ec_slave[slave].FMMU[FMMUc].FMMUtype = 2;
00674             ec_slave[slave].FMMU[FMMUc].FMMUactive = 1;
00675             /* program FMMU for output */
00676             ec_FPWR(configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc), sizeof(ec_fmmut),
00677                     &ec_slave[slave].FMMU[FMMUc], EC_TIMEOUTRET);
00678             /* add two for an output FMMU */
00679             ec_group[group].expectedWKC += 2;
00680             if (!ec_slave[slave].outputs)
00681             {
00682               ec_slave[slave].outputs = pIOmap + etohl(ec_slave[slave].FMMU[FMMUc].LogStart);
00683               ec_slave[slave].Ostartbit = ec_slave[slave].FMMU[FMMUc].LogStartbit;
00684               EC_PRINT("    slave %d Outputs %p startbit %d\n", slave, ec_slave[slave].outputs, ec_slave[slave].Ostartbit);
00685                                         }
00686             FMMUc++;
00687           }
00688           ec_slave[slave].FMMUunused = FMMUc;
00689           diff = LogAddr - oLogAddr;
00690           oLogAddr = LogAddr;
00691           if ((segmentsize + diff) > (EC_MAXLRWDATA - EC_FIRSTDCDATAGRAM))
00692           {
00693             ec_group[group].IOsegment[currentsegment] = segmentsize;
00694             if (currentsegment < (EC_MAXIOSEGMENTS - 1))
00695             {
00696               currentsegment++;
00697               segmentsize = diff;
00698             }
00699           }
00700           else
00701             segmentsize += diff;
00702         }
00703       }
00704     }
00705     if (BitPos)
00706     {
00707       LogAddr++;
00708       oLogAddr = LogAddr;
00709       BitPos = 0;
00710       if ((segmentsize + 1) > (EC_MAXLRWDATA - EC_FIRSTDCDATAGRAM))
00711       {
00712         ec_group[group].IOsegment[currentsegment] = segmentsize;
00713         if (currentsegment < (EC_MAXIOSEGMENTS - 1))
00714         {
00715           currentsegment++;
00716           segmentsize = 1;
00717         }
00718       }
00719       else
00720         segmentsize += 1;
00721     }
00722     ec_group[group].outputs = pIOmap;
00723     ec_group[group].Obytes = LogAddr;
00724     ec_group[group].nsegments = currentsegment + 1;
00725     ec_group[group].Isegment = currentsegment;
00726     ec_group[group].Ioffset = segmentsize;
00727     if (!group)
00728     {
00729       ec_slave[0].outputs = pIOmap;
00730       ec_slave[0].Obytes = LogAddr; /* store output bytes in master record */
00731     }
00732 
00733     /* do input mapping of slave and program FMMUs */
00734     for (slave = 1; slave <= ec_slavecount; slave++)
00735     {
00736       configadr = ec_slave[slave].configadr;
00737       FMMUc = ec_slave[slave].FMMUunused;
00738       if (ec_slave[slave].Obits) /* find free FMMU */
00739         while (ec_slave[slave].FMMU[FMMUc].LogStart)
00740           FMMUc++;
00741       SMc = 0;
00742       BitCount = 0;
00743       ByteCount = 0;
00744       EndAddr = 0;
00745       FMMUsize = 0;
00746       FMMUdone = 0;
00747       /* create input mapping */
00748       if (ec_slave[slave].Ibits)
00749       {
00750         EC_PRINT(" =Slave %d, INPUT MAPPING\n", slave);
00751         /* search for SM that contribute to the input mapping */
00752         while ((SMc < (EC_MAXSM - 1)) && (FMMUdone < ((ec_slave[slave].Ibits + 7) / 8)))
00753         {
00754           EC_PRINT("    FMMU %d\n", FMMUc);
00755           while ((SMc < (EC_MAXSM - 1)) && (ec_slave[slave].SMtype[SMc] != 4))
00756             SMc++;
00757           EC_PRINT("      SM%d\n", SMc);
00758           ec_slave[slave].FMMU[FMMUc].PhysStart = ec_slave[slave].SM[SMc].StartAddr;
00759           SMlength = etohs(ec_slave[slave].SM[SMc].SMlength);
00760           ByteCount += SMlength;
00761           BitCount += SMlength * 8;
00762           EndAddr = etohs(ec_slave[slave].SM[SMc].StartAddr)+ SMlength;
00763           while ((BitCount < ec_slave[slave].Ibits) && (SMc < (EC_MAXSM - 1))) /* more SM for input */
00764           {
00765             SMc++;
00766             while ((SMc < (EC_MAXSM - 1)) && (ec_slave[slave].SMtype[SMc] != 4))
00767               SMc++;
00768             /* if addresses from more SM connect use one FMMU otherwise break up in mutiple FMMU */
00769             if (etohs(ec_slave[slave].SM[SMc].StartAddr)> EndAddr ) break;
00770             EC_PRINT("      SM%d\n", SMc);
00771             SMlength = etohs(ec_slave[slave].SM[SMc].SMlength);
00772             ByteCount += SMlength;
00773             BitCount += SMlength * 8;
00774             EndAddr = etohs(ec_slave[slave].SM[SMc].StartAddr)+ SMlength;
00775           }
00776 
00777           /* bit oriented slave */
00778           if (!ec_slave[slave].Ibytes)
00779           {
00780             ec_slave[slave].FMMU[FMMUc].LogStart = htoel(LogAddr);
00781             ec_slave[slave].FMMU[FMMUc].LogStartbit = BitPos;
00782             BitPos += ec_slave[slave].Ibits - 1;
00783             if (BitPos > 7)
00784             {
00785               LogAddr++;
00786               BitPos -= 8;
00787             }
00788             FMMUsize = LogAddr - etohl(ec_slave[slave].FMMU[FMMUc].LogStart)+ 1;
00789             ec_slave[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
00790             ec_slave[slave].FMMU[FMMUc].LogEndbit = BitPos;
00791             BitPos++;
00792             if (BitPos > 7)
00793             {
00794               LogAddr++;
00795               BitPos -= 8;
00796             }
00797           }
00798           /* byte oriented slave */
00799           else
00800           {
00801             if (BitPos)
00802             {
00803               LogAddr++;
00804               BitPos = 0;
00805             }
00806             ec_slave[slave].FMMU[FMMUc].LogStart = htoel(LogAddr);
00807             ec_slave[slave].FMMU[FMMUc].LogStartbit = BitPos;
00808             BitPos = 7;
00809             FMMUsize = ByteCount;
00810             if ((FMMUsize + FMMUdone) > ec_slave[slave].Ibytes)
00811               FMMUsize = ec_slave[slave].Ibytes - FMMUdone;
00812             LogAddr += FMMUsize;
00813             ec_slave[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
00814             ec_slave[slave].FMMU[FMMUc].LogEndbit = BitPos;
00815             BitPos = 0;
00816           }
00817           FMMUdone += FMMUsize;
00818           if (ec_slave[slave].FMMU[FMMUc].LogLength)
00819           {
00820             ec_slave[slave].FMMU[FMMUc].PhysStartBit = 0;
00821             ec_slave[slave].FMMU[FMMUc].FMMUtype = 1;
00822             ec_slave[slave].FMMU[FMMUc].FMMUactive = 1;
00823             /* program FMMU for input */
00824             ec_FPWR(configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc), sizeof(ec_fmmut),
00825                     &ec_slave[slave].FMMU[FMMUc], EC_TIMEOUTRET);
00826             /* add one for an input FMMU */
00827             ec_group[group].expectedWKC += 1;
00828           }
00829           if (!ec_slave[slave].inputs)
00830           {
00831             ec_slave[slave].inputs = pIOmap + etohl(ec_slave[slave].FMMU[FMMUc].LogStart);
00832             ec_slave[slave].Istartbit = ec_slave[slave].FMMU[FMMUc].LogStartbit;
00833             EC_PRINT("    Inputs %p startbit %d\n", ec_slave[slave].inputs, ec_slave[slave].Istartbit);
00834           }
00835           FMMUc++;
00836         }
00837         ec_slave[slave].FMMUunused = FMMUc;
00838         diff = LogAddr - oLogAddr;
00839         oLogAddr = LogAddr;
00840         if ((segmentsize + diff) > (EC_MAXLRWDATA - EC_FIRSTDCDATAGRAM))
00841         {
00842           ec_group[group].IOsegment[currentsegment] = segmentsize;
00843           if (currentsegment < (EC_MAXIOSEGMENTS - 1))
00844           {
00845             currentsegment++;
00846             segmentsize = diff;
00847           }
00848         }
00849         else
00850           segmentsize += diff;
00851       }
00852 
00853       ec_eeprom2pdi(slave); /* set Eeprom control to PDI */
00854       ec_FPWRw(configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP), EC_TIMEOUTRET); /* set safeop status */
00855 
00856     }
00857     if (BitPos)
00858     {
00859       LogAddr++;
00860       oLogAddr = LogAddr;
00861       BitPos = 0;
00862       if ((segmentsize + 1) > (EC_MAXLRWDATA - EC_FIRSTDCDATAGRAM))
00863       {
00864         ec_group[group].IOsegment[currentsegment] = segmentsize;
00865         if (currentsegment < (EC_MAXIOSEGMENTS - 1))
00866         {
00867           currentsegment++;
00868           segmentsize = 1;
00869         }
00870       }
00871       else
00872         segmentsize += 1;
00873     }
00874     ec_group[group].IOsegment[currentsegment] = segmentsize;
00875     ec_group[group].nsegments = currentsegment + 1;
00876     ec_group[group].inputs = pIOmap + ec_group[group].Obytes;
00877     ec_group[group].Ibytes = LogAddr - ec_group[group].Obytes;
00878     if (ec_slave[slave].blockLRW)
00879       ec_group[group].blockLRW++;
00880     ec_group[group].Ebuscurrent += ec_slave[slave].Ebuscurrent;
00881     if (!group)
00882     {
00883       ec_slave[0].inputs = pIOmap + ec_slave[0].Obytes;
00884       ec_slave[0].Ibytes = LogAddr - ec_slave[0].Obytes; /* store input bytes in master record */
00885     }
00886 
00887     EC_PRINT("IOmapSize %d\n", LogAddr - ec_group[group].logstartaddr);
00888     return (LogAddr - ec_group[group].logstartaddr);
00889   }
00890   return 0;
00891 }
00892 
00898 int ec_config_map(void *pIOmap)
00899 {
00900   return ec_config_map_group(pIOmap, 0);
00901 }
00902 
00909 int ec_config(uint8 usetable, void *pIOmap)
00910 {
00911   int wkc;
00912   wkc = ec_config_init(usetable);
00913   if (wkc)
00914     ec_config_map(pIOmap);
00915   return wkc;
00916 }
00917 
00923 int ec_recover_slave(uint16 slave)
00924 {
00925   int rval;
00926   uint16 ADPh, configadr;
00927 
00928   rval = 0;
00929   configadr = ec_slave[slave].configadr;
00930   /* clear possible slaves at EC_TEMPNODE */
00931   ec_FPWRw(EC_TEMPNODE, ECT_REG_STADR, htoes(0), 0);
00932   ADPh = (uint16)(1 - slave);
00933   /* set temporary node address of slave */
00934   if (ec_APWRw(ADPh, ECT_REG_STADR, htoes(EC_TEMPNODE), EC_TIMEOUTRET) <= 0)
00935     return 0; /* slave fails to respond */
00936 
00937   ec_slave[slave].configadr = EC_TEMPNODE; /* temporary config address */
00938   ec_eeprom2master(slave); /* set Eeprom control to master */
00939 
00940   /* check if slave is the same as configured before */
00941   if ((ec_FPRDw(EC_TEMPNODE, ECT_REG_ALIAS, EC_TIMEOUTRET) == ec_slave[slave].aliasadr)
00942       && (ec_readeeprom(slave, ECT_SII_ID, EC_TIMEOUTEEP) == ec_slave[slave].eep_id)
00943       && (ec_readeeprom(slave, ECT_SII_MANUF, EC_TIMEOUTEEP) == ec_slave[slave].eep_man)
00944       && (ec_readeeprom(slave, ECT_SII_REV, EC_TIMEOUTEEP) == ec_slave[slave].eep_rev))
00945   {
00946     rval = ec_FPWRw(EC_TEMPNODE, ECT_REG_STADR, htoes(configadr), EC_TIMEOUTRET);
00947     ec_slave[slave].configadr = configadr;
00948   }
00949   else
00950   {
00951     /* slave is not the expected one, remove config address*/
00952     ec_FPWRw(EC_TEMPNODE, ECT_REG_STADR, htoes(0), EC_TIMEOUTRET);
00953     ec_slave[slave].configadr = configadr;
00954   }
00955 
00956   return rval;
00957 }
00958 
00964 int ec_reconfig_slave(uint16 slave)
00965 {
00966   int state, nSM, FMMUc;
00967   uint16 configadr;
00968 
00969   configadr = ec_slave[slave].configadr;
00970   if (ec_FPWRw(configadr, ECT_REG_ALCTL, htoes(EC_STATE_INIT), EC_TIMEOUTRET) <= 0)
00971     return 0;
00972   state = 0;
00973   ec_eeprom2pdi(slave); /* set Eeprom control to PDI */
00974   /* check state change init */
00975   state = ec_statecheck(slave, EC_STATE_INIT, EC_TIMEOUTSTATE);
00976   if (state == EC_STATE_INIT)
00977   {
00978     /* program all enabled SM */
00979     for (nSM = 0; nSM < EC_MAXSM; nSM++)
00980     {
00981       if (ec_slave[slave].SM[nSM].StartAddr)
00982         ec_FPWR(configadr, ECT_REG_SM0 + (nSM * sizeof(ec_smt)), sizeof(ec_smt), &ec_slave[slave].SM[nSM],
00983                 EC_TIMEOUTRET);
00984     }
00985     /* program configured FMMU */
00986     for (FMMUc = 0; FMMUc < ec_slave[slave].FMMUunused; FMMUc++)
00987     {
00988       ec_FPWR(configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc), sizeof(ec_fmmut), &ec_slave[slave].FMMU[FMMUc],
00989               EC_TIMEOUTRET);
00990     }
00991     ec_FPWRw(configadr, ECT_REG_ALCTL, htoes(EC_STATE_PRE_OP), EC_TIMEOUTRET);
00992     state = ec_statecheck(slave, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); /* check state change pre-op */
00993     if (state == EC_STATE_PRE_OP)
00994     {
00995       ec_FPWRw(configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP), EC_TIMEOUTRET); /* set safeop status */
00996       state = ec_statecheck(slave, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE); /* check state change safe-op */
00997     }
00998   }
00999   return state;
01000 }


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Oct 6 2014 09:08:01