ethercattype.h
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : ethercattype.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 
00053 #ifndef _EC_TYPE_H
00054 #define _EC_TYPE_H
00055 
00057 #define EC_LITTLE_ENDIAN
00058 
00059 #ifndef PACKED
00060 #define PACKED  __attribute__((__packed__))
00061 #endif
00062 
00063 #include <sys/time.h>
00064 
00065 /* General types */
00066 typedef unsigned char boolean;
00067 #define TRUE                1
00068 #define FALSE               0
00069 typedef signed char int8;
00070 typedef signed short int16;
00071 typedef signed int int32;
00072 typedef unsigned char uint8;
00073 typedef unsigned short uint16;
00074 typedef unsigned int uint32;
00075 typedef signed long long int64;
00076 typedef unsigned long long uint64;
00077 
00079 #define EC_ERROR                        -3
00080 
00081 #define EC_NOFRAME                      -1
00082 
00083 #define EC_OTHERFRAME           -2
00084 
00085 #define EC_MAXECATFRAME         1518
00086 
00087 /* MTU - Ethernet header - length - datagram header - WCK - FCS */
00088 #define EC_MAXLRWDATA           EC_MAXECATFRAME - 14 - 2 - 10 - 2 - 4
00089 //#define EC_MAXLRWDATA         45
00091 #define EC_FIRSTDCDATAGRAM      20
00092 
00093 #define EC_BUFSIZE                      EC_MAXECATFRAME
00094 
00095 #define EC_ECATTYPE                     0x1000
00096 
00097 #define EC_MAXBUF                       16
00098 
00099 #define EC_TIMEOUTRET           500
00100 //#define EC_TIMEOUTRET         20000
00102 #define EC_TIMEOUTSAFE          20000
00103 
00104 #define EC_TIMEOUTEEP           20000
00105 
00106 #define EC_TIMEOUTTXM           20000
00107 
00108 #define EC_TIMEOUTRXM           700000
00109 
00110 #define EC_TIMEOUTSTATE         2000000
00111 
00112 #define EC_MAXEEPBITMAP         128
00113 
00114 #define EC_MAXEEPBUF            EC_MAXEEPBITMAP << 5
00115 
00116 #define EC_DEFAULTRETRIES       3
00117 
00119 typedef uint8 ec_bufT[EC_BUFSIZE];
00120 
00122 typedef struct
00123   PACKED
00124   {
00126     uint16 da0, da1, da2;
00128     uint16 sa0, sa1, sa2;
00130     uint16 etype;
00131   } ec_etherheadert;
00132 
00134 #define ETH_HEADERSIZE          sizeof(ec_etherheadert)
00135 
00137   typedef struct
00138     PACKED
00139     {
00141       uint16 elength;
00143       uint8 command;
00145       uint8 index;
00147       uint16 ADP;
00149       uint16 ADO;
00151       uint16 dlength;
00153       uint16 irpt;
00154     } ec_comt;
00155 
00157 #define EC_HEADERSIZE           sizeof(ec_comt)
00158 
00159 #define EC_ELENGTHSIZE          sizeof(uint16)
00160 
00161 #define EC_CMDOFFSET            EC_ELENGTHSIZE
00162 
00163 #define EC_WKCSIZE                      sizeof(uint16)
00164 
00165 #define EC_DATAGRAMFOLLOWS  (1 << 15)
00166 
00168     typedef enum
00169     {
00171       EC_ERR_OK = 0,
00173       EC_ERR_ALREADY_INITIALIZED,
00175       EC_ERR_NOT_INITIALIZED,
00177       EC_ERR_TIMEOUT,
00179       EC_ERR_NO_SLAVES,
00181       EC_ERR_NOK
00182     } ec_err;
00183 
00185     typedef enum
00186     {
00188       EC_STATE_INIT = 0x01,
00190       EC_STATE_PRE_OP = 0x02,
00192       EC_STATE_BOOT = 0x03,
00194       EC_STATE_SAFE_OP = 0x04,
00196       EC_STATE_OPERATIONAL = 0x08,
00198       EC_STATE_ACK = 0x10, EC_STATE_ERROR = 0x10
00199     } ec_state;
00200 
00202     typedef enum
00203     {
00205       EC_BUF_EMPTY = 0x00,
00207       EC_BUF_ALLOC = 0x01,
00209       EC_BUF_TX = 0x02,
00211       EC_BUF_RCVD = 0x03,
00213       EC_BUF_COMPLETE = 0x04
00214     } ec_bufstate;
00215 
00217     typedef enum
00218     {
00219       ECT_BOOLEAN = 0x0001, ECT_INTEGER8 = 0x0002, ECT_INTEGER16 = 0x0003, ECT_INTEGER32 = 0x0004,
00220       ECT_UNSIGNED8 = 0x0005, ECT_UNSIGNED16 = 0x0006, ECT_UNSIGNED32 = 0x0007, ECT_REAL32 = 0x0008,
00221       ECT_VISIBLE_STRING = 0x0009, ECT_OCTET_STRING = 0x000A, ECT_UNICODE_STRING = 0x000B, ECT_TIME_OF_DAY = 0x000C,
00222       ECT_TIME_DIFFERENCE = 0x000D, ECT_DOMAIN = 0x000F, ECT_INTEGER24 = 0x0010, ECT_REAL64 = 0x0011,
00223       ECT_INTEGER64 = 0x0015, ECT_UNSIGNED24 = 0x0016, ECT_UNSIGNED64 = 0x001B, ECT_BIT1 = 0x0030, ECT_BIT2 = 0x0031,
00224       ECT_BIT3 = 0x0032, ECT_BIT4 = 0x0033, ECT_BIT5 = 0x0034, ECT_BIT6 = 0x0035, ECT_BIT7 = 0x0036, ECT_BIT8 = 0x0037
00225     } ec_datatype;
00226 
00228     typedef enum
00229     {
00231       EC_CMD_NOP = 0x00,
00233       EC_CMD_APRD,
00235       EC_CMD_APWR,
00237       EC_CMD_APRW,
00239       EC_CMD_FPRD,
00241       EC_CMD_FPWR,
00243       EC_CMD_FPRW,
00245       EC_CMD_BRD,
00247       EC_CMD_BWR,
00249       EC_CMD_BRW,
00251       EC_CMD_LRD,
00253       EC_CMD_LWR,
00255       EC_CMD_LRW,
00257       EC_CMD_ARMW,
00259       EC_CMD_FRMW
00261     } ec_cmdtype;
00262 
00264     typedef enum
00265     {
00267       EC_ECMD_NOP = 0x0000,
00269       EC_ECMD_READ = 0x0100,
00271       EC_ECMD_WRITE = 0x0201,
00273       EC_ECMD_RELOAD = 0x0300
00274     } ec_ecmdtype;
00275 
00277 #define EC_ESTAT_R64    0x0040
00278 
00279 #define EC_ESTAT_BUSY   0x8000
00280 
00281 #define EC_ESTAT_EMASK  0x7800
00282 
00283 #define EC_ESTAT_NACK   0x2000
00284 
00285     /* Ethercat SSI (Slave Information Interface) */
00286 
00288 #define ECT_SII_START   0x0040
00289 
00290     enum
00291     {
00293       ECT_SII_STRING = 10,
00295       ECT_SII_GENERAL = 30,
00297       ECT_SII_FMMU = 40,
00299       ECT_SII_SM = 41,
00301       ECT_SII_PDO = 50
00302     };
00303 
00305     enum
00306     {
00307       ECT_SII_MANUF = 0x0008, ECT_SII_ID = 0x000a, ECT_SII_REV = 0x000c, ECT_SII_BOOTRXMBX = 0x0014,
00308       ECT_SII_BOOTTXMBX = 0x0016, ECT_SII_MBXSIZE = 0x0019, ECT_SII_TXMBXADR = 0x001a, ECT_SII_RXMBXADR = 0x0018,
00309       ECT_SII_MBXPROTO = 0x001c
00310 
00311     };
00312 
00314     enum
00315     {
00317       ECT_MBXT_ERR = 0x00,
00319       ECT_MBXT_AOE,
00321       ECT_MBXT_EOE,
00323       ECT_MBXT_COE,
00325       ECT_MBXT_FOE,
00327       ECT_MBXT_SOE,
00329       ECT_MBXT_VOE = 0x0f
00330     };
00331 
00333     enum
00334     {
00335       ECT_COES_EMERGENCY = 0x01, ECT_COES_SDOREQ, ECT_COES_SDORES, ECT_COES_TXPDO, ECT_COES_RXPDO, ECT_COES_TXPDO_RR,
00336       ECT_COES_RXPDO_RR, ECT_COES_SDOINFO
00337     };
00338 
00340     enum
00341     {
00342       ECT_SDO_DOWN_INIT = 0x21, ECT_SDO_DOWN_INIT_CA = 0x31, ECT_SDO_UP_REQ = 0x40, ECT_SDO_UP_REQ_CA = 0x50,
00343       ECT_SDO_SEG_UP_REQ = 0x60, ECT_SDO_ABORT = 0x80
00344     };
00345 
00347     enum
00348     {
00349       ECT_GET_ODLIST_REQ = 0x01, ECT_GET_ODLIST_RES = 0x02, ECT_GET_OD_REQ = 0x03, ECT_GET_OD_RES = 0x04,
00350       ECT_GET_OE_REQ = 0x05, ECT_GET_OE_RES = 0x06, ECT_SDOINFO_ERROR = 0x07
00351     };
00352 
00354     enum
00355     {
00356       ECT_FOE_READ = 0x01, ECT_FOE_WRITE, ECT_FOE_DATA, ECT_FOE_ACK, ECT_FOE_ERROR, ECT_FOE_BUSY
00357     };
00358 
00360     enum
00361     {
00362       ECT_SOE_READREQ = 0x01, ECT_SOE_READRES, ECT_SOE_WRITEREQ, ECT_SOE_WRITERES, ECT_SOE_NOTIFICATION,
00363       ECT_SOE_EMERGENCY
00364     };
00365 
00367     enum
00368     {
00369       ECT_REG_TYPE = 0x0000, ECT_REG_PORTDES = 0x0007, ECT_REG_ESCSUP = 0x0008, ECT_REG_STADR = 0x0010,
00370       ECT_REG_ALIAS = 0x0012, ECT_REG_DLCTL = 0x0100, ECT_REG_DLPORT = 0x0101, ECT_REG_DLALIAS = 0x0103,
00371       ECT_REG_DLSTAT = 0x0110, ECT_REG_ALCTL = 0x0120, ECT_REG_ALSTAT = 0x0130, ECT_REG_ALSTATCODE = 0x0134,
00372       ECT_REG_PDICTL = 0x0140, ECT_REG_IRQMASK = 0x0200, ECT_REG_RXERR = 0x0300, ECT_REG_EEPCFG = 0x0500,
00373       ECT_REG_EEPCTL = 0x0502, ECT_REG_EEPSTAT = 0x0502, ECT_REG_EEPADR = 0x0504, ECT_REG_EEPDAT = 0x0508,
00374       ECT_REG_FMMU0 = 0x0600, ECT_REG_FMMU1 = ECT_REG_FMMU0 + 0x10, ECT_REG_FMMU2 = ECT_REG_FMMU1 + 0x10,
00375       ECT_REG_FMMU3 = ECT_REG_FMMU2 + 0x10, ECT_REG_SM0 = 0x0800, ECT_REG_SM1 = ECT_REG_SM0 + 0x08,
00376       ECT_REG_SM2 = ECT_REG_SM1 + 0x08, ECT_REG_SM3 = ECT_REG_SM2 + 0x08, ECT_REG_SM0STAT = ECT_REG_SM0 + 0x05,
00377       ECT_REG_SM1STAT = ECT_REG_SM1 + 0x05, ECT_REG_SM1ACT = ECT_REG_SM1 + 0x06, ECT_REG_SM1CONTR = ECT_REG_SM1 + 0x07,
00378       ECT_REG_DCTIME0 = 0x0900, ECT_REG_DCTIME1 = 0x0904, ECT_REG_DCTIME2 = 0x0908, ECT_REG_DCTIME3 = 0x090C,
00379       ECT_REG_DCSYSTIME = 0x0910, ECT_REG_DCSOF = 0x0918, ECT_REG_DCSYSOFFSET = 0x0920, ECT_REG_DCSYSDELAY = 0x0928,
00380       ECT_REG_DCSYSDIFF = 0x092C, ECT_REG_DCSPEEDCNT = 0x0930, ECT_REG_DCTIMEFILT = 0x0934, ECT_REG_DCCUC = 0x0980,
00381       ECT_REG_DCSYNCACT = 0x0981, ECT_REG_DCSTART0 = 0x0990, ECT_REG_DCCYCLE0 = 0x09A0, ECT_REG_DCCYCLE1 = 0x09A4
00382     };
00383 
00385 #define ECT_SDO_SMCOMMTYPE              0x1c00
00386 
00387 #define ECT_SDO_PDOASSIGN               0x1c10
00388 
00389 #define ECT_SDO_RXPDOASSIGN     0x1c12
00390 
00391 #define ECT_SDO_TXPDOASSIGN     0x1c13
00392 
00394 #define ETH_P_ECAT              0x88A4
00395 
00397     typedef enum
00398     {
00399       EC_ERR_TYPE_SDO_ERROR = 0, EC_ERR_TYPE_EMERGENCY = 1, EC_ERR_TYPE_PACKET_ERROR = 3, EC_ERR_TYPE_SDOINFO_ERROR = 4,
00400       EC_ERR_TYPE_FOE_ERROR = 5, EC_ERR_TYPE_FOE_BUF2SMALL = 6, EC_ERR_TYPE_FOE_PACKETNUMBER = 7,
00401       EC_ERR_TYPE_SOE_ERROR = 8
00402     } ec_err_type;
00403 
00405     typedef struct
00406     {
00408       struct timeval Time;
00410       boolean Signal;
00412       uint16 Slave;
00414       uint16 Index;
00416       uint8 SubIdx;
00418       ec_err_type Etype;
00419       union
00420       {
00422         int32 AbortCode;
00424         struct
00425         {
00426           uint16 ErrorCode;
00427           uint8 ErrorReg;
00428           uint8 b1;
00429           uint16 w1;
00430           uint16 w2;
00431         };
00432       };
00433     } ec_errort;
00434 
00437 #define MK_WORD(msb, lsb)   ((((uint16)(msb))<<8) | (lsb))
00438 
00439 #define HI_BYTE(w)          ((w) >> 8)
00440 
00441 #define LO_BYTE(w)          ((w) & 0x00ff)
00442 
00443 #define SWAP(w)             ((((w)& 0xff00) >> 8) | (((w) & 0x00ff) << 8))
00444 
00445 #define LO_WORD(l)          ((l) & 0xffff)
00446 
00447 #define HI_WORD(l)          ((l) >> 16)
00448 
00449 #define get_unaligned(ptr) \
00450   ({ __typeof__(*(ptr)) __tmp; memcpy(&__tmp, (ptr), sizeof(*(ptr))); __tmp; })
00451 
00452 #define put_unaligned32(val, ptr)        \
00453   ({   memcpy((ptr), &(val), 4);         \
00454       (void)0; })
00455 
00456 #define put_unaligned64(val, ptr)        \
00457   ({   memcpy((ptr), &(val), 8);         \
00458       (void)0; })
00459 
00460 #if !defined(EC_BIG_ENDIAN) && defined(EC_LITTLE_ENDIAN)
00461 
00462 #define htoes(A) (A)
00463 #define htoel(A) (A)
00464 #define htoell(A) (A)
00465 #define etohs(A) (A)
00466 #define etohl(A) (A)
00467 #define etohll(A) (A)
00468 
00469 #elif !defined(EC_LITTLE_ENDIAN) && defined(EC_BIG_ENDIAN)
00470 
00471 #define htoes(A) ((((uint16)(A) & 0xff00) >> 8) | \
00472                     (((uint16)(A) & 0x00ff) << 8))
00473 #define htoel(A) ((((uint32)(A) & 0xff000000) >> 24) | \
00474                     (((uint32)(A) & 0x00ff0000) >> 8)  | \
00475                     (((uint32)(A) & 0x0000ff00) << 8)  | \
00476                     (((uint32)(A) & 0x000000ff) << 24))
00477 #define htoell(A) ((((uint64)(A) & (uint64)0xff00000000000000ULL) >> 56) | \
00478                      (((uint64)(A) & (uint64)0x00ff000000000000ULL) >> 40) | \
00479                      (((uint64)(A) & (uint64)0x0000ff0000000000ULL) >> 24) | \
00480                      (((uint64)(A) & (uint64)0x000000ff00000000ULL) >> 8)  | \
00481                      (((uint64)(A) & (uint64)0x00000000ff000000ULL) << 8)  | \
00482                      (((uint64)(A) & (uint64)0x0000000000ff0000ULL) << 24) | \
00483                      (((uint64)(A) & (uint64)0x000000000000ff00ULL) << 40) | \
00484                      (((uint64)(A) & (uint64)0x00000000000000ffULL) << 56))
00485 
00486 #define etohs  htoes
00487 #define etohl  htoel
00488 #define etohll htoell
00489 
00490 #else
00491 
00492 #error "Must define one of EC_BIG_ENDIAN or EC_LITTLE_ENDIAN"
00493 
00494 #endif
00495 
00496 #endif /* _EC_TYPE_H */


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