ethercatmain.h
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : ethercatmain.h
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 
00046 #ifndef _ethercatmain_
00047 #define _ethercatmain_
00048 
00049 #ifndef PACKED
00050 #define PACKED  __attribute__((__packed__))
00051 #endif
00052 
00054 #define EC_MAXELIST             64
00055 
00056 #define EC_MAXNAME              36
00057 
00058 #define EC_MAXSLAVE             200
00059 
00060 #define EC_MAXGROUP             8
00061 
00062 #define EC_MAXIOSEGMENTS 64
00063 
00064 #define EC_MAXMBX               0x3ff
00065 
00066 #define EC_MAXEEPDO             0x200
00067 
00068 #define EC_MAXSM                8
00069 
00070 #define EC_MAXFMMU              4
00071 
00073 typedef struct
00074   PACKED
00075   {
00076     uint32 LogStart;
00077     uint16 LogLength;
00078     uint8 LogStartbit;
00079     uint8 LogEndbit;
00080     uint16 PhysStart;
00081     uint8 PhysStartBit;
00082     uint8 FMMUtype;
00083     uint8 FMMUactive;
00084     uint8 unused1;
00085     uint16 unused2;
00086   } ec_fmmut;
00087 
00089   typedef struct
00090     PACKED
00091     {
00092       uint16 StartAddr;
00093       uint16 SMlength;
00094       uint32 SMflags;
00095     } ec_smt;
00096 
00097     typedef struct
00098       PACKED
00099       {
00100         uint16 State;
00101         uint16 Unused;
00102         uint16 ALstatuscode;
00103       } ec_state_status;
00104 
00105 #define ECT_MBXPROT_AOE         0x0001
00106 #define ECT_MBXPROT_EOE         0x0002
00107 #define ECT_MBXPROT_COE         0x0004
00108 #define ECT_MBXPROT_FOE         0x0008
00109 #define ECT_MBXPROT_SOE         0x0010
00110 #define ECT_MBXPROT_VOE         0x0020
00111 
00112 #define ECT_COEDET_SDO                  0x01
00113 #define ECT_COEDET_SDOINFO              0x02
00114 #define ECT_COEDET_PDOASSIGN    0x04
00115 #define ECT_COEDET_PDOCONFIG    0x08
00116 #define ECT_COEDET_UPLOAD               0x10
00117 #define ECT_COEDET_SDOCA                0x20
00118 
00119 #define EC_SMENABLEMASK         0xfffeffff
00120 
00122       typedef struct
00123       {
00125         uint16 state;
00127         uint16 ALstatuscode;
00129         uint16 configadr;
00131         uint16 aliasadr;
00133         uint32 eep_man;
00135         uint32 eep_id;
00137         uint32 eep_rev;
00139         uint16 Itype;
00141         uint16 Dtype;
00143         uint16 Obits;
00145         uint32 Obytes;
00147         uint8 *outputs;
00149         uint8 Ostartbit;
00151         uint16 Ibits;
00153         uint32 Ibytes;
00155         uint8 *inputs;
00157         uint8 Istartbit;
00159         ec_smt SM[EC_MAXSM];
00161         uint8 SMtype[EC_MAXSM];
00163         ec_fmmut FMMU[EC_MAXFMMU];
00165         uint8 FMMU0func;
00167         uint8 FMMU1func;
00169         uint8 FMMU2func;
00171         uint8 FMMU3func;
00173         uint16 mbx_l;
00175         uint16 mbx_wo;
00177         uint16 mbx_rl;
00179         uint16 mbx_ro;
00181         uint16 mbx_proto;
00183         uint8 mbx_cnt;
00185         boolean hasdc;
00187         uint8 ptype;
00189         uint8 topology;
00191         uint8 activeports;
00193         uint8 consumedports;
00195         uint16 parent;
00197         uint8 parentport;
00199         uint8 entryport;
00201         int32 DCrtA;
00203         int32 DCrtB;
00205         int32 DCrtC;
00207         int32 DCrtD;
00209         int32 pdelay;
00211         uint16 DCnext;
00213         uint16 DCprevious;
00215         int32 DCcycle;
00217         int32 DCshift;
00219         uint8 DCactive;
00221         uint16 configindex;
00223         uint16 SIIindex;
00225         uint8 eep_8byte;
00227         uint8 eep_pdi;
00229         uint8 CoEdetails;
00231         uint8 FoEdetails;
00233         uint8 EoEdetails;
00235         uint8 SoEdetails;
00237         int16 Ebuscurrent;
00239         uint8 blockLRW;
00241         uint8 group;
00243         uint8 FMMUunused;
00245         boolean islost;
00247         int (*PO2SOconfig)(uint16 slave);
00249         char name[EC_MAXNAME + 1];
00250       } ec_slavet;
00251 
00253       typedef struct
00254       {
00256         uint32 logstartaddr;
00258         uint32 Obytes;
00260         uint8 *outputs;
00262         uint32 Ibytes;
00264         uint8 *inputs;
00266         boolean hasdc;
00268         uint16 DCnext;
00270         int16 Ebuscurrent;
00272         uint8 blockLRW;
00274         uint16 nsegments;
00276         uint16 Isegment;
00278         uint16 Ioffset;
00280         uint16 expectedWKC;
00282         boolean docheckstate;
00284         uint32 IOsegment[EC_MAXIOSEGMENTS];
00285       } ec_groupt;
00286 
00288       typedef struct
00289       {
00290         uint16 Startpos;
00291         uint8 nFMMU;
00292         uint8 FMMU0;
00293         uint8 FMMU1;
00294         uint8 FMMU2;
00295         uint8 FMMU3;
00296       } ec_eepromFMMUt;
00297 
00299       typedef struct
00300       {
00301         uint16 Startpos;
00302         uint8 nSM;
00303         uint16 PhStart;
00304         uint16 Plength;
00305         uint8 Creg;
00306         uint8 Sreg; /* dont care */
00307         uint8 Activate;
00308         uint8 PDIctrl; /* dont care */
00309       } ec_eepromSMt;
00310 
00312       typedef struct
00313       {
00314         uint16 Startpos;
00315         uint16 Length;
00316         uint16 nPDO;
00317         uint16 Index[EC_MAXEEPDO];
00318         uint16 SyncM[EC_MAXEEPDO];
00319         uint16 BitSize[EC_MAXEEPDO];
00320         uint16 SMbitsize[EC_MAXSM];
00321       } ec_eepromPDOt;
00322 
00324       typedef uint8 ec_mbxbuft[EC_MAXMBX + 1];
00325 
00327       typedef struct
00328         PACKED
00329         {
00330           uint16 length;
00331           uint16 address;
00332           uint8 priority;
00333           uint8 mbxtype;
00334         } ec_mbxheadert;
00335 
00337         typedef struct
00338           PACKED
00339           {
00340             uint16 alstatus;
00341             uint16 unused;
00342             uint16 alstatuscode;
00343           } ec_alstatust;
00344 
00346           extern ec_slavet ec_slave[EC_MAXSLAVE];
00348           extern int ec_slavecount;
00350           extern ec_groupt ec_group[EC_MAXGROUP];
00351           extern boolean EcatError;
00352 
00353           extern uint16 ec_DCtO;
00354           extern int64 ec_DCtime;
00355 
00356           void ec_pusherror(const ec_errort *Ec);
00357           boolean ec_poperror(ec_errort *Ec);
00358           boolean ec_iserror(void);
00359           void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode);
00360           int ec_init(const char * ifname);
00361           int ec_init_redundant(const char *ifname, const char *if2name);
00362           void ec_close(void);
00363           uint8 ec_siigetbyte(uint16 slave, uint16 address);
00364           int16 ec_siifind(uint16 slave, uint16 cat);
00365           void ec_siistring(char *str, uint16 slave, uint16 Sn);
00366           uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU);
00367           uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM);
00368           uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n);
00369           int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t);
00370           int ec_readstate(void);
00371           int ec_writestate(uint16 slave);
00372           uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout);
00373           uint8 ec_nextmbxcnt(uint8 cnt);
00374           void ec_clearmbx(ec_mbxbuft *Mbx);
00375           int ec_mbxempty(uint16 slave, int timeout);
00376           int ec_mbxsend(uint16 slave, ec_mbxbuft *mbx, int timeout);
00377           int ec_mbxreceive(uint16 slave, ec_mbxbuft *mbx, int timeout);
00378           void ec_esidump(uint16 slave, uint8 *esibuf, uint8 test);
00379           uint32 ec_readeeprom(uint16 slave, uint16 eeproma, int timeout);
00380           int ec_writeeeprom(uint16 slave, uint16 eeproma, uint16 data, int timeout);
00381           int ec_eeprom2master(uint16 slave);
00382           int ec_eeprom2pdi(uint16 slave);
00383           uint64 ec_readeepromAP(uint16 aiadr, uint16 eeproma, int timeout);
00384           int ec_writeeepromAP(uint16 aiadr, uint16 eeproma, uint16 data, int timeout);
00385           uint64 ec_readeepromFP(uint16 configadr, uint16 eeproma, int timeout);
00386           int ec_writeeepromFP(uint16 configadr, uint16 eeproma, uint16 data, int timeout);
00387           void ec_readeeprom1(uint16 slave, uint16 eeproma);
00388           uint32 ec_readeeprom2(uint16 slave, int timeout);
00389           int ec_send_processdata_group(uint8 group);
00390           int ec_receive_processdata_group(uint8 group, int timeout);
00391           int ec_send_processdata(void);
00392           int ec_receive_processdata(int timeout);
00393 
00394 #endif


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