nicdrv.c
Go to the documentation of this file.
00001 /*
00002  * Simple Open EtherCAT Master Library 
00003  *
00004  * File    : nicdrv.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 
00068 #include <sys/types.h>
00069 #include <sys/ioctl.h>
00070 #include <net/if.h> 
00071 #include <sys/socket.h> 
00072 #include <unistd.h>
00073 #include <sys/time.h> 
00074 #include <time.h>
00075 #include <arpa/inet.h>
00076 #include <stdio.h>
00077 #include <fcntl.h>
00078 #include <string.h>
00079 #include <netpacket/packet.h>
00080 #include <pthread.h>
00081 
00082 #include "ethercat_soem/oshw.h"
00083 #include "ethercat_soem/osal.h"
00084 
00086 enum
00087 {
00089    ECT_RED_NONE,
00091    ECT_RED_DOUBLE
00092 };
00093 
00094 
00101 const uint16 priMAC[3] = { 0x0101, 0x0101, 0x0101 };
00103 const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
00104 
00106 #define RX_PRIM priMAC[1]
00107 
00108 #define RX_SEC secMAC[1]
00109 
00116 int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary) 
00117 {
00118    int i;
00119    int r, rval, ifindex;
00120    struct timeval timeout;
00121    struct ifreq ifr;
00122    struct sockaddr_ll sll;
00123    int *psock;
00124 
00125    rval = 0;
00126    if (secondary)
00127    {
00128       /* secondary port stuct available? */
00129       if (port->redport)
00130       {
00131          /* when using secondary socket it is automatically a redundant setup */
00132          psock = &(port->redport->sockhandle);
00133          *psock = -1;
00134          port->redstate                   = ECT_RED_DOUBLE;
00135          port->redport->stack.sock        = &(port->redport->sockhandle);
00136          port->redport->stack.txbuf       = &(port->txbuf);
00137          port->redport->stack.txbuflength = &(port->txbuflength);
00138          port->redport->stack.tempbuf     = &(port->redport->tempinbuf);
00139          port->redport->stack.rxbuf       = &(port->redport->rxbuf);
00140          port->redport->stack.rxbufstat   = &(port->redport->rxbufstat);
00141          port->redport->stack.rxsa        = &(port->redport->rxsa);
00142       }
00143       else
00144       {
00145          /* fail */
00146          return 0;
00147       }
00148    }
00149    else
00150    {
00151       pthread_mutex_init(&(port->getindex_mutex), NULL);
00152       pthread_mutex_init(&(port->tx_mutex)      , NULL);
00153       pthread_mutex_init(&(port->rx_mutex)      , NULL);
00154       port->sockhandle        = -1;
00155       port->lastidx           = 0;
00156       port->redstate          = ECT_RED_NONE;
00157       port->stack.sock        = &(port->sockhandle);
00158       port->stack.txbuf       = &(port->txbuf);
00159       port->stack.txbuflength = &(port->txbuflength);
00160       port->stack.tempbuf     = &(port->tempinbuf);
00161       port->stack.rxbuf       = &(port->rxbuf);
00162       port->stack.rxbufstat   = &(port->rxbufstat);
00163       port->stack.rxsa        = &(port->rxsa);
00164       psock = &(port->sockhandle);
00165    }   
00166    /* we use RAW packet socket, with packet type ETH_P_ECAT */
00167    *psock = socket(PF_PACKET, SOCK_RAW, htons(ETH_P_ECAT));
00168    
00169    timeout.tv_sec =  0;
00170    timeout.tv_usec = 1; 
00171    r = setsockopt(*psock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof(timeout));
00172    r = setsockopt(*psock, SOL_SOCKET, SO_SNDTIMEO, &timeout, sizeof(timeout));
00173    i = 1;
00174    r = setsockopt(*psock, SOL_SOCKET, SO_DONTROUTE, &i, sizeof(i));
00175    /* connect socket to NIC by name */
00176    strcpy(ifr.ifr_name, ifname);
00177    r = ioctl(*psock, SIOCGIFINDEX, &ifr);
00178    ifindex = ifr.ifr_ifindex;
00179    strcpy(ifr.ifr_name, ifname);
00180    ifr.ifr_flags = 0;
00181    /* reset flags of NIC interface */
00182    r = ioctl(*psock, SIOCGIFFLAGS, &ifr);
00183    /* set flags of NIC interface, here promiscuous and broadcast */
00184    ifr.ifr_flags = ifr.ifr_flags || IFF_PROMISC || IFF_BROADCAST;
00185    r = ioctl(*psock, SIOCGIFFLAGS, &ifr);
00186    /* bind socket to protocol, in this case RAW EtherCAT */
00187    sll.sll_family = AF_PACKET;
00188    sll.sll_ifindex = ifindex;
00189    sll.sll_protocol = htons(ETH_P_ECAT);
00190    r = bind(*psock, (struct sockaddr *)&sll, sizeof(sll));
00191    /* setup ethernet headers in tx buffers so we don't have to repeat it */
00192    for (i = 0; i < EC_MAXBUF; i++) 
00193    {
00194       ec_setupheader(&(port->txbuf[i]));
00195       port->rxbufstat[i] = EC_BUF_EMPTY;
00196    }
00197    ec_setupheader(&(port->txbuf2));
00198    if (r == 0) rval = 1;
00199    
00200    return rval;
00201 }
00202 
00207 int ecx_closenic(ecx_portt *port) 
00208 {
00209    if (port->sockhandle >= 0) 
00210       close(port->sockhandle);
00211    if ((port->redport) && (port->redport->sockhandle >= 0))
00212       close(port->redport->sockhandle);
00213    
00214    return 0;
00215 }
00216 
00222 void ec_setupheader(void *p) 
00223 {
00224    ec_etherheadert *bp;
00225    bp = p;
00226    bp->da0 = htons(0xffff);
00227    bp->da1 = htons(0xffff);
00228    bp->da2 = htons(0xffff);
00229    bp->sa0 = htons(priMAC[0]);
00230    bp->sa1 = htons(priMAC[1]);
00231    bp->sa2 = htons(priMAC[2]);
00232    bp->etype = htons(ETH_P_ECAT);
00233 }
00234 
00239 int ecx_getindex(ecx_portt *port)
00240 {
00241    int idx;
00242    int cnt;
00243 
00244    pthread_mutex_lock( &(port->getindex_mutex) );
00245 
00246    idx = port->lastidx + 1;
00247    /* index can't be larger than buffer array */
00248    if (idx >= EC_MAXBUF) 
00249    {
00250       idx = 0;
00251    }
00252    cnt = 0;
00253    /* try to find unused index */
00254    while ((port->rxbufstat[idx] != EC_BUF_EMPTY) && (cnt < EC_MAXBUF))
00255    {
00256       idx++;
00257       cnt++;
00258       if (idx >= EC_MAXBUF) 
00259       {
00260          idx = 0;
00261       }
00262    }
00263    port->rxbufstat[idx] = EC_BUF_ALLOC;
00264    if (port->redstate != ECT_RED_NONE)
00265       port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
00266    port->lastidx = idx;
00267 
00268    pthread_mutex_unlock( &(port->getindex_mutex) );
00269    
00270    return idx;
00271 }
00272 
00278 void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
00279 {
00280    port->rxbufstat[idx] = bufstat;
00281    if (port->redstate != ECT_RED_NONE)
00282       port->redport->rxbufstat[idx] = bufstat;
00283 }
00284 
00291 int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
00292 {
00293    int lp, rval;
00294    ec_stackT *stack;
00295 
00296    if (!stacknumber)
00297    {
00298       stack = &(port->stack);
00299    }
00300    else
00301    {
00302       stack = &(port->redport->stack);
00303    }
00304    lp = (*stack->txbuflength)[idx];
00305    rval = send(*stack->sock, (*stack->txbuf)[idx], lp, 0);
00306    (*stack->rxbufstat)[idx] = EC_BUF_TX;
00307    
00308    return rval;
00309 }
00310 
00316 int ecx_outframe_red(ecx_portt *port, int idx)
00317 {
00318    ec_comt *datagramP;
00319    ec_etherheadert *ehp;
00320    int rval;
00321 
00322    ehp = (ec_etherheadert *)&(port->txbuf[idx]);
00323    /* rewrite MAC source address 1 to primary */
00324    ehp->sa1 = htons(priMAC[1]);
00325    /* transmit over primary socket*/
00326    rval = ecx_outframe(port, idx, 0);
00327    if (port->redstate != ECT_RED_NONE)
00328    {   
00329       pthread_mutex_lock( &(port->tx_mutex) );
00330       ehp = (ec_etherheadert *)&(port->txbuf2);
00331       /* use dummy frame for secondary socket transmit (BRD) */
00332       datagramP = (ec_comt*)&(port->txbuf2[ETH_HEADERSIZE]);
00333       /* write index to frame */
00334       datagramP->index = idx;
00335       /* rewrite MAC source address 1 to secondary */
00336       ehp->sa1 = htons(secMAC[1]);
00337       /* transmit over secondary socket */
00338       send(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2 , 0);
00339       pthread_mutex_unlock( &(port->tx_mutex) );
00340       port->redport->rxbufstat[idx] = EC_BUF_TX;
00341    }   
00342    
00343    return rval;
00344 }
00345 
00351 static int ecx_recvpkt(ecx_portt *port, int stacknumber)
00352 {
00353    int lp, bytesrx;
00354    ec_stackT *stack;
00355 
00356    if (!stacknumber)
00357    {
00358       stack = &(port->stack);
00359    }
00360    else
00361    {
00362       stack = &(port->redport->stack);
00363    }
00364    lp = sizeof(port->tempinbuf);
00365    bytesrx = recv(*stack->sock, (*stack->tempbuf), lp, 0);
00366    port->tempinbufs = bytesrx;
00367    
00368    return (bytesrx > 0);
00369 }
00370 
00387 int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
00388 {
00389    uint16  l;
00390    int     rval;
00391    int     idxf;
00392    ec_etherheadert *ehp;
00393    ec_comt *ecp;
00394    ec_stackT *stack;
00395    ec_bufT *rxbuf;
00396 
00397    if (!stacknumber)
00398    {
00399       stack = &(port->stack);
00400    }
00401    else
00402    {
00403       stack = &(port->redport->stack);
00404    }
00405    rval = EC_NOFRAME;
00406    rxbuf = &(*stack->rxbuf)[idx];
00407    /* check if requested index is already in buffer ? */
00408    if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD)) 
00409    {
00410       l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
00411       /* return WKC */
00412       rval = ((*rxbuf)[l] + ((uint16)(*rxbuf)[l + 1] << 8));
00413       /* mark as completed */
00414       (*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
00415    }
00416    else 
00417    {
00418       pthread_mutex_lock(&(port->rx_mutex));
00419       /* non blocking call to retrieve frame from socket */
00420       if (ecx_recvpkt(port, stacknumber)) 
00421       {
00422          rval = EC_OTHERFRAME;
00423          ehp =(ec_etherheadert*)(stack->tempbuf);
00424          /* check if it is an EtherCAT frame */
00425          if (ehp->etype == htons(ETH_P_ECAT)) 
00426          {
00427             ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]); 
00428             l = etohs(ecp->elength) & 0x0fff;
00429             idxf = ecp->index;
00430             /* found index equals reqested index ? */
00431             if (idxf == idx) 
00432             {
00433                /* yes, put it in the buffer array (strip ethernet header) */
00434                memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
00435                /* return WKC */
00436                rval = ((*rxbuf)[l] + ((uint16)((*rxbuf)[l + 1]) << 8));
00437                /* mark as completed */
00438                (*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
00439                /* store MAC source word 1 for redundant routing info */
00440                (*stack->rxsa)[idx] = ntohs(ehp->sa1);
00441             }
00442             else 
00443             {
00444                /* check if index exist? */
00445                if (idxf < EC_MAXBUF) 
00446                {
00447                   rxbuf = &(*stack->rxbuf)[idxf];
00448                   /* put it in the buffer array (strip ethernet header) */
00449                   memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idxf] - ETH_HEADERSIZE);
00450                   /* mark as received */
00451                   (*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
00452                   (*stack->rxsa)[idxf] = ntohs(ehp->sa1);
00453                }
00454                else 
00455                {
00456                   /* strange things happend */
00457                }
00458             }
00459          }
00460       }
00461       pthread_mutex_unlock( &(port->rx_mutex) );
00462       
00463    }
00464    
00465    /* WKC if mathing frame found */
00466    return rval;
00467 }
00468 
00481 static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
00482 {
00483    osal_timert timer2;
00484    int wkc  = EC_NOFRAME;
00485    int wkc2 = EC_NOFRAME;
00486    int primrx, secrx;
00487    
00488    /* if not in redundant mode then always assume secondary is OK */
00489    if (port->redstate == ECT_RED_NONE)
00490       wkc2 = 0;
00491    do 
00492    {
00493       /* only read frame if not already in */
00494       if (wkc <= EC_NOFRAME)
00495          wkc  = ecx_inframe(port, idx, 0);
00496       /* only try secondary if in redundant mode */
00497       if (port->redstate != ECT_RED_NONE)
00498       {   
00499          /* only read frame if not already in */
00500          if (wkc2 <= EC_NOFRAME)
00501             wkc2 = ecx_inframe(port, idx, 1);
00502       }   
00503    /* wait for both frames to arrive or timeout */   
00504    } while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
00505    /* only do redundant functions when in redundant mode */
00506    if (port->redstate != ECT_RED_NONE)
00507    {
00508       /* primrx if the reveived MAC source on primary socket */
00509       primrx = 0;
00510       if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
00511       /* secrx if the reveived MAC source on psecondary socket */
00512       secrx = 0;
00513       if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
00514       
00515       /* primary socket got secondary frame and secondary socket got primary frame */
00516       /* normal situation in redundant mode */
00517       if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
00518       {
00519          /* copy secondary buffer to primary */
00520          memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
00521          wkc = wkc2;
00522       }   
00523       /* primary socket got nothing or primary frame, and secondary socket got secondary frame */
00524       /* we need to resend TX packet */ 
00525       if ( ((primrx == 0) && (secrx == RX_SEC)) ||
00526            ((primrx == RX_PRIM) && (secrx == RX_SEC)) )
00527       {
00528          /* If both primary and secondary have partial connection retransmit the primary received
00529           * frame over the secondary socket. The result from the secondary received frame is a combined
00530           * frame that traversed all slaves in standard order. */
00531          if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
00532          {   
00533             /* copy primary rx to tx buffer */
00534             memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
00535          }
00536          osal_timer_start (&timer2, EC_TIMEOUTRET);
00537          /* resend secondary tx */
00538          ecx_outframe(port, idx, 1);
00539          do 
00540          {
00541             /* retrieve frame */
00542             wkc2 = ecx_inframe(port, idx, 1);
00543          } while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
00544          if (wkc2 > EC_NOFRAME)
00545          {   
00546             /* copy secondary result to primary rx buffer */
00547             memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
00548             wkc = wkc2;
00549          }   
00550       }      
00551    }
00552    
00553    /* return WKC or EC_NOFRAME */
00554    return wkc;
00555 }   
00556 
00564 int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
00565 {
00566    int wkc;
00567    osal_timert timer;
00568    
00569    osal_timer_start (&timer, timeout); 
00570    wkc = ecx_waitinframe_red(port, idx, &timer);
00571    /* if nothing received, clear buffer index status so it can be used again */
00572    if (wkc <= EC_NOFRAME) 
00573    {
00574       ecx_setbufstat(port, idx, EC_BUF_EMPTY);
00575    }
00576    
00577    return wkc;
00578 }
00579 
00592 int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
00593 {
00594    int wkc = EC_NOFRAME;
00595    osal_timert timer1, timer2;
00596 
00597    osal_timer_start (&timer1, timeout);
00598    do 
00599    {
00600       /* tx frame on primary and if in redundant mode a dummy on secondary */
00601       ecx_outframe_red(port, idx);
00602       if (timeout < EC_TIMEOUTRET) 
00603       {
00604          osal_timer_start (&timer2, timeout); 
00605       }
00606       else 
00607       {
00608          /* normally use partial timout for rx */
00609          osal_timer_start (&timer2, EC_TIMEOUTRET); 
00610       }
00611       /* get frame from primary or if in redundant mode possibly from secondary */
00612       wkc = ecx_waitinframe_red(port, idx, &timer2);
00613    /* wait for answer with WKC>=0 or otherwise retry until timeout */   
00614    } while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
00615    /* if nothing received, clear buffer index status so it can be used again */
00616    if (wkc <= EC_NOFRAME) 
00617    {
00618       ecx_setbufstat(port, idx, EC_BUF_EMPTY);
00619    }
00620    
00621    return wkc;
00622 }
00623 
00624 #ifdef EC_VER1
00625 int ec_setupnic(const char *ifname, int secondary)
00626 {
00627    return ecx_setupnic(&ecx_port, ifname, secondary);
00628 }
00629 
00630 int ec_closenic(void)
00631 {
00632    return ecx_closenic(&ecx_port);
00633 }
00634 
00635 int ec_getindex(void)
00636 {
00637    return ecx_getindex(&ecx_port);
00638 }
00639 
00640 void ec_setbufstat(int idx, int bufstat)
00641 {
00642    ecx_setbufstat(&ecx_port, idx, bufstat);
00643 }
00644 
00645 int ec_outframe(int idx, int stacknumber)
00646 {
00647    return ecx_outframe(&ecx_port, idx, stacknumber);
00648 }
00649 
00650 int ec_outframe_red(int idx)
00651 {
00652    return ecx_outframe_red(&ecx_port, idx);
00653 }
00654 
00655 int ec_inframe(int idx, int stacknumber)
00656 {
00657    return ecx_inframe(&ecx_port, idx, stacknumber);
00658 }
00659 
00660 int ec_waitinframe(int idx, int timeout)
00661 {
00662    return ecx_waitinframe(&ecx_port, idx, timeout);
00663 }
00664 
00665 int ec_srconfirm(int idx, int timeout)
00666 {
00667    return ecx_srconfirm(&ecx_port, idx, timeout);
00668 }
00669 #endif


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