ethercatmain.h
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : ethercatmain.h
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, Eiserstrasse 5, D-33415 Verl, Germany
00038  * (www.beckhoff.com).
00039  */
00040 
00046 #ifndef _ethercatmain_
00047 #define _ethercatmain_
00048 
00049 
00050 #ifdef __cplusplus
00051 extern "C"
00052 {
00053 #endif
00054 
00056 #define EC_MAXELIST       64
00057 
00058 #define EC_MAXNAME        40
00059 
00060 #define EC_MAXSLAVE       200
00061 
00062 #define EC_MAXGROUP       2
00063 
00064 #define EC_MAXIOSEGMENTS  64
00065 
00066 #define EC_MAXMBX         0x3ff
00067 
00068 #define EC_MAXEEPDO       0x200
00069 
00070 #define EC_MAXSM          8
00071 
00072 #define EC_MAXFMMU        4
00073 
00074 #define EC_MAXLEN_ADAPTERNAME    128
00075 
00076 typedef struct ec_adapter ec_adaptert;
00077 struct ec_adapter
00078 {
00079    char   name[EC_MAXLEN_ADAPTERNAME];
00080    char   desc[EC_MAXLEN_ADAPTERNAME];
00081    ec_adaptert *next;
00082 };
00083 
00085 PACKED_BEGIN
00086 typedef struct PACKED
00087 {
00088    uint32  LogStart;
00089    uint16  LogLength;
00090    uint8   LogStartbit;
00091    uint8   LogEndbit;
00092    uint16  PhysStart;
00093    uint8   PhysStartBit;
00094    uint8   FMMUtype;
00095    uint8   FMMUactive;
00096    uint8   unused1;
00097    uint16  unused2;  
00098 }  ec_fmmut;
00099 PACKED_END
00100 
00102 PACKED_BEGIN
00103 typedef struct PACKED
00104 {
00105    uint16  StartAddr;
00106    uint16  SMlength;
00107    uint32  SMflags;
00108 } ec_smt;
00109 PACKED_END
00110 
00111 PACKED_BEGIN
00112 typedef struct PACKED
00113 {
00114    uint16  State;
00115    uint16  Unused;
00116    uint16  ALstatuscode;
00117 } ec_state_status;
00118 PACKED_END
00119 
00120 #define ECT_MBXPROT_AOE      0x0001
00121 #define ECT_MBXPROT_EOE      0x0002
00122 #define ECT_MBXPROT_COE      0x0004
00123 #define ECT_MBXPROT_FOE      0x0008
00124 #define ECT_MBXPROT_SOE      0x0010
00125 #define ECT_MBXPROT_VOE      0x0020
00126 
00127 #define ECT_COEDET_SDO       0x01
00128 #define ECT_COEDET_SDOINFO   0x02
00129 #define ECT_COEDET_PDOASSIGN 0x04
00130 #define ECT_COEDET_PDOCONFIG 0x08
00131 #define ECT_COEDET_UPLOAD    0x10
00132 #define ECT_COEDET_SDOCA     0x20
00133 
00134 #define EC_SMENABLEMASK      0xfffeffff
00135 
00137 typedef struct
00138 {
00140    uint16           state;
00142    uint16           ALstatuscode;
00144    uint16           configadr;
00146    uint16           aliasadr;
00148    uint32           eep_man;
00150    uint32           eep_id;
00152    uint32           eep_rev;
00154    uint16           Itype;
00156    uint16           Dtype;
00158    uint16           Obits;
00160    uint32           Obytes;
00162    uint8            *outputs;
00164    uint8            Ostartbit;
00166    uint16           Ibits;
00168    uint32           Ibytes;
00170    uint8            *inputs;
00172    uint8            Istartbit;
00174    ec_smt           SM[EC_MAXSM];
00176    uint8            SMtype[EC_MAXSM];
00178    ec_fmmut         FMMU[EC_MAXFMMU];
00180    uint8            FMMU0func;
00182    uint8            FMMU1func;
00184    uint8            FMMU2func;
00186    uint8            FMMU3func;
00188    uint16           mbx_l;
00190    uint16           mbx_wo;
00192    uint16           mbx_rl;
00194    uint16           mbx_ro;
00196    uint16           mbx_proto;
00198    uint8            mbx_cnt;
00200    boolean          hasdc;
00202    uint8            ptype;
00204    uint8            topology;
00206    uint8            activeports;
00208    uint8            consumedports;
00210    uint16           parent;
00212    uint8            parentport;
00214    uint8            entryport;
00216    int32            DCrtA;
00218    int32            DCrtB; 
00220    int32            DCrtC;
00222    int32            DCrtD;
00224    int32            pdelay;
00226    uint16           DCnext;
00228    uint16           DCprevious;
00230    int32            DCcycle;
00232    int32            DCshift;
00234    uint8            DCactive;
00236    uint16           configindex;
00238    uint16           SIIindex;
00240    uint8            eep_8byte;
00242    uint8            eep_pdi;
00244    uint8            CoEdetails;
00246    uint8            FoEdetails;
00248    uint8            EoEdetails;
00250    uint8            SoEdetails;
00252    int16            Ebuscurrent;
00254    uint8            blockLRW;
00256    uint8            group;
00258    uint8            FMMUunused;
00260    boolean          islost;
00262    int              (*PO2SOconfig)(uint16 slave);
00264    char             name[EC_MAXNAME + 1];
00265 } ec_slavet;
00266 
00268 typedef struct
00269 {
00271    uint32           logstartaddr;
00273    uint32           Obytes;
00275    uint8            *outputs;
00277    uint32           Ibytes;
00279    uint8            *inputs;
00281    boolean          hasdc;
00283    uint16           DCnext;
00285    int16            Ebuscurrent;
00287    uint8            blockLRW;
00289    uint16           nsegments;
00291    uint16           Isegment;
00293    uint16           Ioffset;
00295    uint16           outputsWKC;
00297    uint16           inputsWKC;
00299    boolean          docheckstate;
00301    uint32           IOsegment[EC_MAXIOSEGMENTS];
00302 } ec_groupt;
00303 
00305 typedef struct
00306 {
00307    uint16  Startpos;
00308    uint8   nFMMU;
00309    uint8   FMMU0;
00310    uint8   FMMU1;
00311    uint8   FMMU2;
00312    uint8   FMMU3;
00313 } ec_eepromFMMUt;
00314 
00316 typedef struct
00317 {
00318    uint16  Startpos;
00319    uint8   nSM;
00320    uint16  PhStart;
00321    uint16  Plength;
00322    uint8   Creg;
00323    uint8   Sreg;       /* dont care */
00324    uint8   Activate;
00325    uint8   PDIctrl;      /* dont care */
00326 } ec_eepromSMt;
00327 
00329 typedef struct 
00330 {
00331    uint16  Startpos;
00332    uint16  Length;
00333    uint16  nPDO;
00334    uint16  Index[EC_MAXEEPDO];
00335    uint16  SyncM[EC_MAXEEPDO];
00336    uint16  BitSize[EC_MAXEEPDO];
00337    uint16  SMbitsize[EC_MAXSM];
00338 } ec_eepromPDOt;
00339 
00341 typedef uint8 ec_mbxbuft[EC_MAXMBX + 1];
00342 
00344 PACKED_BEGIN
00345 typedef struct PACKED
00346 {
00347    uint16  length;
00348    uint16  address;
00349    uint8   priority;
00350    uint8   mbxtype;
00351 } ec_mbxheadert;
00352 PACKED_END
00353 
00355 PACKED_BEGIN
00356 typedef struct PACKED
00357 {
00358    uint16  alstatus;
00359    uint16  unused;
00360    uint16  alstatuscode;
00361 } ec_alstatust;
00362 PACKED_END
00363 
00365 typedef struct
00366 {
00367    uint8   pushed;
00368    uint8   pulled;
00369    uint8   idx[EC_MAXBUF];
00370    void    *data[EC_MAXBUF];
00371    uint16  length[EC_MAXBUF];
00372 } ec_idxstackT;
00373 
00375 typedef struct 
00376 {
00377    int16     head;
00378    int16     tail;
00379    ec_errort Error[EC_MAXELIST + 1];
00380 } ec_eringt;
00381 
00383 PACKED_BEGIN
00384 typedef struct PACKED
00385 {
00386    uint8   n;
00387    uint8   nu1;
00388    uint8   SMtype[EC_MAXSM];
00389 } ec_SMcommtypet;   
00390 PACKED_END
00391 
00393 PACKED_BEGIN
00394 typedef struct PACKED
00395 {
00396    uint8   n;
00397    uint8   nu1;
00398    uint16  index[256];
00399 } ec_PDOassignt;   
00400 PACKED_END
00401 
00403 PACKED_BEGIN
00404 typedef struct PACKED
00405 {
00406    uint8   n;
00407    uint8   nu1;
00408    uint32  PDO[256];
00409 } ec_PDOdesct;   
00410 PACKED_END
00411 
00413 typedef struct
00414 {
00416    ecx_portt      *port;
00418    ec_slavet      *slavelist;
00420    int            *slavecount;
00422    int            maxslave;
00424    ec_groupt      *grouplist;
00426    int            maxgroup;
00428    uint8          *esibuf;
00430    uint32         *esimap;
00432    uint16         esislave;
00434    ec_eringt      *elist;
00436    ec_idxstackT   *idxstack;
00438    boolean        *ecaterror;
00440    uint16         DCtO;
00442    uint16         DCl;
00444    int64          *DCtime;
00446    ec_SMcommtypet *SMcommtype;
00448    ec_PDOassignt  *PDOassign;
00450    ec_PDOdesct    *PDOdesc;
00452    ec_eepromSMt   *eepSM;
00454    ec_eepromFMMUt *eepFMMU; 
00456    int            (*FOEhook)(uint16 slave, int packetnumber, int datasize);
00457 } ecx_contextt;
00458 
00459 #ifdef EC_VER1
00460 
00461 extern ecx_contextt  ecx_context;
00463 extern ec_slavet   ec_slave[EC_MAXSLAVE];
00465 extern int         ec_slavecount;
00467 extern ec_groupt   ec_group[EC_MAXGROUP];
00468 extern boolean     EcatError;
00469 extern int64       ec_DCtime;
00470 
00471 void ec_pusherror(const ec_errort *Ec);
00472 boolean ec_poperror(ec_errort *Ec);
00473 boolean ec_iserror(void);
00474 void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode);
00475 int ec_init(char * ifname);
00476 int ec_init_redundant(char *ifname, char *if2name);
00477 void ec_close(void);
00478 uint8 ec_siigetbyte(uint16 slave, uint16 address);
00479 int16 ec_siifind(uint16 slave, uint16 cat);
00480 void ec_siistring(char *str, uint16 slave, uint16 Sn);
00481 uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU);
00482 uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM);
00483 uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n);
00484 int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t);
00485 int ec_readstate(void);
00486 int ec_writestate(uint16 slave);
00487 uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout);
00488 int ec_mbxempty(uint16 slave, int timeout);
00489 int ec_mbxsend(uint16 slave,ec_mbxbuft *mbx, int timeout);
00490 int ec_mbxreceive(uint16 slave, ec_mbxbuft *mbx, int timeout);
00491 void ec_esidump(uint16 slave, uint8 *esibuf);
00492 uint32 ec_readeeprom(uint16 slave, uint16 eeproma, int timeout);
00493 int ec_writeeeprom(uint16 slave, uint16 eeproma, uint16 data, int timeout);
00494 int ec_eeprom2master(uint16 slave);
00495 int ec_eeprom2pdi(uint16 slave);
00496 uint64 ec_readeepromAP(uint16 aiadr, uint16 eeproma, int timeout);
00497 int ec_writeeepromAP(uint16 aiadr, uint16 eeproma, uint16 data, int timeout);
00498 uint64 ec_readeepromFP(uint16 configadr, uint16 eeproma, int timeout);
00499 int ec_writeeepromFP(uint16 configadr, uint16 eeproma, uint16 data, int timeout);
00500 void ec_readeeprom1(uint16 slave, uint16 eeproma);
00501 uint32 ec_readeeprom2(uint16 slave, int timeout);
00502 int ec_send_processdata_group(uint8 group);
00503 int ec_receive_processdata_group(uint8 group, int timeout);
00504 int ec_send_processdata(void);
00505 int ec_receive_processdata(int timeout);
00506 #endif
00507 
00508 ec_adaptert * ec_find_adapters(void);
00509 void ec_free_adapters(ec_adaptert * adapter);
00510 uint8 ec_nextmbxcnt(uint8 cnt);
00511 void ec_clearmbx(ec_mbxbuft *Mbx);
00512 void ecx_pusherror(ecx_contextt *context, const ec_errort *Ec);
00513 boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec);
00514 boolean ecx_iserror(ecx_contextt *context);
00515 void ecx_packeterror(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode);
00516 int ecx_init(ecx_contextt *context, char * ifname);
00517 int ecx_init_redundant(ecx_contextt *context, ecx_redportt *redport, char *ifname, char *if2name);
00518 void ecx_close(ecx_contextt *context);
00519 uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address);
00520 int16 ecx_siifind(ecx_contextt *context, uint16 slave, uint16 cat);
00521 void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn);
00522 uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt* FMMU);
00523 uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM);
00524 uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint16 n);
00525 int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t);
00526 int ecx_readstate(ecx_contextt *context);
00527 int ecx_writestate(ecx_contextt *context, uint16 slave);
00528 uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout);
00529 int ecx_mbxempty(ecx_contextt *context, uint16 slave, int timeout);
00530 int ecx_mbxsend(ecx_contextt *context, uint16 slave,ec_mbxbuft *mbx, int timeout);
00531 int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout);
00532 void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf);
00533 uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout);
00534 int ecx_writeeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout);
00535 int ecx_eeprom2master(ecx_contextt *context, uint16 slave);
00536 int ecx_eeprom2pdi(ecx_contextt *context, uint16 slave);
00537 uint64 ecx_readeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout);
00538 int ecx_writeeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout);
00539 uint64 ecx_readeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout);
00540 int ecx_writeeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout);
00541 void ecx_readeeprom1(ecx_contextt *context, uint16 slave, uint16 eeproma);
00542 uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout);
00543 int ecx_send_processdata_group(ecx_contextt *context, uint8 group);
00544 int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeout);
00545 int ecx_send_processdata(ecx_contextt *context);
00546 int ecx_receive_processdata(ecx_contextt *context, int timeout);
00547 
00548 #ifdef __cplusplus
00549 }
00550 #endif
00551 
00552 #endif


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