vxworks/nicdrv.c
Go to the documentation of this file.
1 /*
2  * Licensed under the GNU General Public License version 2 with exceptions. See
3  * LICENSE file in the project root for full license information
4  */
5 
34 #include <vxWorks.h>
35 #include <ctype.h>
36 #include <string.h>
37 #include <stdio.h>
38 #include <muxLib.h>
39 #include <ipProto.h>
40 #include <wvLib.h>
41 #include <sysLib.h>
42 
43 #include "oshw.h"
44 #include "osal.h"
45 #include "nicdrv.h"
46 
47 #define NIC_DEBUG /* Print debugging info? */
48 
49 // wvEvent flags
50 #define ECAT_RECV_FAILED 0x664
51 #define ECAT_RECV_OK 0x665
52 #define ECAT_RECV_RETRY_OK 0x666
53 #define ECAT_STACK_RECV 0x667
54 #define ECAT_SEND_START 0x675
55 #define ECAT_SEND_COMPLETE 0x676
56 #define ECAT_SEND_FAILED 0x677
57 
58 #ifdef NIC_DEBUG
59 
60 #define NIC_LOGMSG(x,a,b,c,d,e,f) \
61  do { \
62  logMsg (x,a,b,c,d,e,f); \
63  } while (0)
64 #define NIC_WVEVENT(a,b,c) \
65  do { \
66  wvEvent(a, b, c); \
67  } while (0)
68 
69 
70 #else
71 #define NIC_LOGMSG(x,a,b,c,d,e,f)
72 #define NIC_WVEVENT(a,b,c)
73 #endif /* NIC_DEBUG */
74 
75 #define IF_NAME_SIZE 8
76 
78 enum
79 {
84 };
85 
86 
93 const uint16 priMAC[3] = { 0x0101, 0x0101, 0x0101 };
95 const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
96 
98 #define RX_PRIM priMAC[1]
99 
100 #define RX_SEC secMAC[1]
101 
102 /* usec per tick for timeconversion, default to 1kHz */
103 #define USECS_PER_SEC 1000000
104 static unsigned int usec_per_tick = 1000;
105 
107 static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg);
108 
109 static void ecx_clear_rxbufstat(int *rxbufstat)
110 {
111  int i;
112  for(i = 0; i < EC_MAXBUF; i++)
113  {
114  rxbufstat[i] = EC_BUF_EMPTY;
115  }
116 }
117 
119 {
120  printf("Generic is used\n");
121 }
122 
129 int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
130 {
131  int i;
132  char ifn[IF_NAME_SIZE];
133  int unit_no = -1;
134  ETHERCAT_PKT_DEV * pPktDev;
135 
136  /* Get systick info, sysClkRateGet return ticks per second */
137  usec_per_tick = USECS_PER_SEC / sysClkRateGet();
138  /* Don't allow 0 since it is used in DIV */
139  if(usec_per_tick == 0)
140  usec_per_tick = 1;
141  /* Make reference to packet device struct, keep track if the packet
142  * device is the redundant or not.
143  */
144  if (secondary)
145  {
146  pPktDev = &(port->redport->pktDev);
147  pPktDev->redundant = 1;
148  }
149  else
150  {
151  pPktDev = &(port->pktDev);
152  pPktDev->redundant = 0;
153  }
154 
155  /* Clear frame counters*/
156  pPktDev->tx_count = 0;
157  pPktDev->rx_count = 0;
158  pPktDev->overrun_count = 0;
159 
160  /* Create multi-thread support semaphores */
161  port->sem_get_index = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE);
162 
163  /* Get the dev name and unit from ifname
164  * We assume form gei1, fei0...
165  */
166  memset(ifn,0x0,sizeof(ifn));
167 
168  for(i=0; i < strlen(ifname);i++)
169  {
170  if(isdigit(ifname[i]))
171  {
172  strncpy(ifn, ifname, i);
173  unit_no = atoi(&ifname[i]);
174  break;
175  }
176  }
177 
178  /* Detach IP stack */
179  //ipDetach(pktDev.unit,pktDev.name);
180 
181  pPktDev->port = port;
182 
183  /* Bind to mux driver for given interface, include ethercat driver pointer
184  * as user reference
185  */
186  /* Bind to mux */
187  pPktDev->pCookie = muxBind(ifn,
188  unit_no,
190  NULL,
191  NULL,
192  NULL,
193  MUX_PROTO_SNARF,
194  "ECAT SNARF",
195  pPktDev);
196 
197  if (pPktDev->pCookie == NULL)
198  {
199  /* fail */
200  NIC_LOGMSG("ecx_setupnic: muxBind init for gei: %d failed\n",
201  unit_no, 2, 3, 4, 5, 6);
202  goto exit;
203  }
204 
205  /* Get reference tp END obje */
206  pPktDev->endObj = endFindByName(ifn, unit_no);
207 
208  if (port->pktDev.endObj == NULL)
209  {
210  /* fail */
211  NIC_LOGMSG("error_hook: endFindByName failed, device gei: %d not found\n",
212  unit_no, 2, 3, 4, 5, 6);
213  goto exit;
214  }
215 
216  if (secondary)
217  {
218  /* secondary port struct available? */
219  if (port->redport)
220  {
221  port->redstate = ECT_RED_DOUBLE;
222  port->redport->stack.txbuf = &(port->txbuf);
223  port->redport->stack.txbuflength = &(port->txbuflength);
224  port->redport->stack.rxbuf = &(port->redport->rxbuf);
225  port->redport->stack.rxbufstat = &(port->redport->rxbufstat);
226  port->redport->stack.rxsa = &(port->redport->rxsa);
227  /* Create mailboxes for each potential EtherCAT frame index */
228  for (i = 0; i < EC_MAXBUF; i++)
229  {
230  port->redport->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
231  if (port->redport->msgQId[i] == MSG_Q_ID_NULL)
232  {
233  NIC_LOGMSG("ecx_setupnic: Failed to create redundant MsgQ[%d]",
234  i, 2, 3, 4, 5, 6);
235  goto exit;
236  }
237  }
238  ecx_clear_rxbufstat(&(port->redport->rxbufstat[0]));
239  }
240  else
241  {
242  /* fail */
243  NIC_LOGMSG("ecx_setupnic: Redundant port not allocated",
244  unit_no, 2, 3, 4, 5, 6);
245  goto exit;
246  }
247  }
248  else
249  {
250  port->lastidx = 0;
251  port->redstate = ECT_RED_NONE;
252  port->stack.txbuf = &(port->txbuf);
253  port->stack.txbuflength = &(port->txbuflength);
254  port->stack.rxbuf = &(port->rxbuf);
255  port->stack.rxbufstat = &(port->rxbufstat);
256  port->stack.rxsa = &(port->rxsa);
257  /* Create mailboxes for each potential EtherCAT frame index */
258  for (i = 0; i < EC_MAXBUF; i++)
259  {
260  port->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
261  if (port->msgQId[i] == MSG_Q_ID_NULL)
262  {
263  NIC_LOGMSG("ecx_setupnic: Failed to create MsgQ[%d]",
264  i, 2, 3, 4, 5, 6);
265  goto exit;
266  }
267  }
268  ecx_clear_rxbufstat(&(port->rxbufstat[0]));
269  }
270 
271  /* setup ethernet headers in tx buffers so we don't have to repeat it */
272  for (i = 0; i < EC_MAXBUF; i++)
273  {
274  ec_setupheader(&(port->txbuf[i]));
275  port->rxbufstat[i] = EC_BUF_EMPTY;
276  }
277  ec_setupheader(&(port->txbuf2));
278 
279  return 1;
280 
281 exit:
282 
283  return 0;
284 
285 }
286 
292 {
293  int i;
294  ETHERCAT_PKT_DEV * pPktDev;
295  M_BLK_ID trash_can;
296 
297  pPktDev = &(port->pktDev);
298 
299  for (i = 0; i < EC_MAXBUF; i++)
300  {
301  if (port->msgQId[i] != MSG_Q_ID_NULL)
302  {
303  if (msgQReceive(port->msgQId[i],
304  (char *)&trash_can,
305  sizeof(M_BLK_ID),
306  NO_WAIT) != ERROR)
307  {
308  NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
309  2, 3, 4, 5, 6);
310  /* Free resources */
311  netMblkClChainFree(trash_can);
312  }
313  msgQDelete(port->msgQId[i]);
314  }
315  }
316 
317  if (pPktDev->pCookie != NULL)
318  {
319  muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
320  }
321 
322  /* Clean redundant resources if available*/
323  if (port->redport)
324  {
325  pPktDev = &(port->redport->pktDev);
326  for (i = 0; i < EC_MAXBUF; i++)
327  {
328  if (port->redport->msgQId[i] != MSG_Q_ID_NULL)
329  {
330  if (msgQReceive(port->redport->msgQId[i],
331  (char *)&trash_can,
332  sizeof(M_BLK_ID),
333  NO_WAIT) != ERROR)
334  {
335  NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
336  2, 3, 4, 5, 6);
337  /* Free resources */
338  netMblkClChainFree(trash_can);
339  }
340  msgQDelete(port->redport->msgQId[i]);
341  }
342  }
343  if (pPktDev->pCookie != NULL)
344  {
345  muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
346  }
347  }
348 
349  return 0;
350 }
351 
357 void ec_setupheader(void *p)
358 {
359  ec_etherheadert *bp;
360  bp = p;
361  bp->da0 = htons(0xffff);
362  bp->da1 = htons(0xffff);
363  bp->da2 = htons(0xffff);
364  bp->sa0 = htons(priMAC[0]);
365  bp->sa1 = htons(priMAC[1]);
366  bp->sa2 = htons(priMAC[2]);
367  bp->etype = htons(ETH_P_ECAT);
368 }
369 
375 {
376  int idx;
377  int cnt;
378 
379  semTake(port->sem_get_index, WAIT_FOREVER);
380 
381  idx = port->lastidx + 1;
382  /* index can't be larger than buffer array */
383  if (idx >= EC_MAXBUF)
384  {
385  idx = 0;
386  }
387  cnt = 0;
388  /* try to find unused index */
389  while ((port->rxbufstat[idx] != EC_BUF_EMPTY) && (cnt < EC_MAXBUF))
390  {
391  idx++;
392  cnt++;
393  if (idx >= EC_MAXBUF)
394  {
395  idx = 0;
396  }
397  }
398  port->rxbufstat[idx] = EC_BUF_ALLOC;
399  port->lastidx = idx;
400 
401  semGive(port->sem_get_index);
402 
403  return idx;
404 }
405 
411 void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
412 {
413  port->rxbufstat[idx] = bufstat;
414  if (port->redstate != ECT_RED_NONE)
415  port->redport->rxbufstat[idx] = bufstat;
416 }
417 
426 static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, int idx, void * buf, int len)
427 {
428  STATUS status = OK;
429  M_BLK_ID pPacket = NULL;
430  int rval = 0;
431  END_OBJ *endObj = (END_OBJ *)pPktDev->endObj;
432  MSG_Q_ID msgQId;
433 
434  /* Clean up any abandoned frames and re-use the allocated buffer*/
435  msgQId = pPktDev->port->msgQId[idx];
436  if(msgQNumMsgs(msgQId) > 0)
437  {
438  pPktDev->abandoned_count++;
439  NIC_LOGMSG("ec_outfram_send: idx %d MsgQ abandoned\n", idx,
440  2, 3, 4, 5, 6);
441  if (msgQReceive(msgQId,
442  (char *)&pPacket,
443  sizeof(M_BLK_ID),
444  NO_WAIT) == ERROR)
445  {
446  pPacket = NULL;
447  NIC_LOGMSG("ec_outfram_send: idx %d MsgQ mBlk handled by receiver\n", idx,
448  2, 3, 4, 5, 6);
449  }
450  }
451 
452  if (pPacket == NULL)
453  {
454  /* Allocate m_blk to send */
455  if ((pPacket = netTupleGet(endObj->pNetPool,
456  len,
457  M_DONTWAIT,
458  MT_DATA,
459  TRUE)) == NULL)
460  {
461  NIC_LOGMSG("ec_outfram_send: Could not allocate MBLK memory!\n", 1, 2, 3, 4, 5, 6);
462  return ERROR;
463  }
464  }
465 
466  pPacket->mBlkHdr.mLen = len;
467  pPacket->mBlkHdr.mFlags |= M_PKTHDR;
468  pPacket->mBlkHdr.mData = pPacket->pClBlk->clNode.pClBuf;
469  pPacket->mBlkPktHdr.len = pPacket->m_len;
470 
471  netMblkFromBufCopy(pPacket, buf, 0, pPacket->mBlkHdr.mLen, M_DONTWAIT, NULL);
472  status = muxSend(endObj, pPacket);
473 
474  if (status == OK)
475  {
476  rval = len;
477  NIC_WVEVENT(ECAT_SEND_COMPLETE, (char *)&rval, sizeof(rval));
478  }
479  else
480  {
481  netMblkClChainFree(pPacket);
482  /* fail */
483  static int print_once;
484  if (print_once == 0)
485  {
486  NIC_LOGMSG("ec_outfram_send: failed\n",
487  1, 2, 3, 4, 5, 6);
488  print_once = 1;
489  }
490  NIC_WVEVENT(ECAT_SEND_FAILED, (char *)&rval, sizeof(rval));
491  }
492 
493  return rval;
494 }
495 
503 int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
504 {
505  int rval = 0;
506  ec_stackT *stack;
507  ETHERCAT_PKT_DEV * pPktDev;
508 
509  if (!stacknumber)
510  {
511  stack = &(port->stack);
512  pPktDev = &(port->pktDev);
513  }
514  else
515  {
516  stack = &(port->redport->stack);
517  pPktDev = &(port->redport->pktDev);
518  }
519 
520  (*stack->rxbufstat)[idx] = EC_BUF_TX;
521  rval = ec_outfram_send(pPktDev, idx, (char*)(*stack->txbuf)[idx],
522  (*stack->txbuflength)[idx]);
523  if (rval > 0)
524  {
525  port->pktDev.tx_count++;
526  }
527  else
528  {
529  (*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
530  }
531 
532  return rval;
533 }
534 
540 int ecx_outframe_red(ecx_portt *port, int idx)
541 {
542  ec_comt *datagramP;
543  ec_etherheadert *ehp;
544  int rval;
545 
546  ehp = (ec_etherheadert *)&(port->txbuf[idx]);
547  /* rewrite MAC source address 1 to primary */
548  ehp->sa1 = htons(priMAC[1]);
549  /* transmit over primary socket*/
550  rval = ecx_outframe(port, idx, 0);
551  if (port->redstate != ECT_RED_NONE)
552  {
553  ehp = (ec_etherheadert *)&(port->txbuf2);
554  /* use dummy frame for secondary socket transmit (BRD) */
555  datagramP = (ec_comt*)&(port->txbuf2[ETH_HEADERSIZE]);
556  /* write index to frame */
557  datagramP->index = idx;
558  /* rewrite MAC source address 1 to secondary */
559  ehp->sa1 = htons(secMAC[1]);
560  /* transmit over secondary interface */
561  port->redport->rxbufstat[idx] = EC_BUF_TX;
562  rval = ec_outfram_send(&(port->redport->pktDev), idx, &(port->txbuf2), port->txbuflength2);
563  if (rval <= 0)
564  {
565  port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
566  }
567  }
568 
569  return rval;
570 }
571 
572 
581 static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg)
582 {
583  BOOL ret = FALSE;
584  int idxf;
585  ec_comt *ecp;
586  ec_bufT * tempbuf;
587  ecx_portt * port;
588  MSG_Q_ID msgQId;
589  ETHERCAT_PKT_DEV * pPktDev;
590  int length;
591  int bufstat;
592 
593  /* check if it is an EtherCAT frame */
594  if (type == ETH_P_ECAT)
595  {
596  length = pMblk->mBlkHdr.mLen;
597  tempbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
598  pPktDev = (ETHERCAT_PKT_DEV *)muxUserArg;
599  port = pPktDev->port;
600 
601  /* Get ethercat frame header */
602  ecp = (ec_comt*)&(*tempbuf)[ETH_HEADERSIZE];
603  idxf = ecp->index;
604  if (idxf >= EC_MAXBUF)
605  {
606  NIC_LOGMSG("mux_rx_callback: idx %d out of bounds\n", idxf,
607  2, 3, 4, 5, 6);
608  return ret;
609  }
610 
611  /* Check if it is the redundant port or not */
612  if (pPktDev->redundant == 1)
613  {
614  bufstat = port->redport->rxbufstat[idxf];
615  msgQId = port->redport->msgQId[idxf];
616  }
617  else
618  {
619  bufstat = port->rxbufstat[idxf];
620  msgQId = port->msgQId[idxf];
621  }
622 
623  /* Check length and if someone expects the frame */
624  if (length > 0 && bufstat == EC_BUF_TX)
625  {
626  /* Post the frame to the receive Q for the EtherCAT stack */
627  STATUS status;
628  status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
629  NO_WAIT, MSG_PRI_NORMAL);
630  if (status == OK)
631  {
632  NIC_WVEVENT(ECAT_RECV_OK, (char *)&length, sizeof(length));
633  ret = TRUE;
634  }
635  else if ((status == ERROR) && (errno == S_objLib_OBJ_UNAVAILABLE))
636  {
637  /* Try to empty the MSGQ since we for some strange reason
638  * already have a frame in the MsqQ,
639  * is it due to timeout when receiving?
640  * We want the latest received frame in the buffer
641  */
642  port->pktDev.overrun_count++;
643  NIC_LOGMSG("mux_rx_callback: idx %d MsgQ overrun\n", idxf,
644  2, 3, 4, 5, 6);
645  M_BLK_ID trash_can;
646  if (msgQReceive(msgQId,
647  (char *)&trash_can,
648  sizeof(M_BLK_ID),
649  NO_WAIT) != ERROR)
650  {
651  /* Free resources */
652  netMblkClChainFree(trash_can);
653  }
654  status = msgQSend(msgQId,
655  (char *)&pMblk,
656  sizeof(M_BLK_ID),
657  NO_WAIT,
658  MSG_PRI_NORMAL);
659  if (status == OK)
660  {
661  NIC_WVEVENT(ECAT_RECV_RETRY_OK, (char *)&length, sizeof(length));
662  ret = TRUE;
663  }
664  }
665  else
666  {
667  NIC_WVEVENT(ECAT_RECV_FAILED, (char *)&length, sizeof(length));
668  }
669  }
670  }
671 
672  return ret;
673 }
674 
681 static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID * pMblk, int timeout)
682 {
683  int bytesrx = 0;
684  MSG_Q_ID msgQId;
685  int tick_timeout = max((timeout / usec_per_tick), 1);
686 
687  if (stacknumber == 1)
688  {
689  msgQId = port->redport->msgQId[idx];
690  }
691  else
692  {
693  msgQId = port->msgQId[idx];
694  }
695 
696  if (timeout == 0)
697  {
698  bytesrx = msgQReceive(msgQId, (void *)pMblk,
699  sizeof(M_BLK_ID), NO_WAIT);
700  }
701  else
702  {
703  bytesrx = msgQReceive(msgQId, (void *)pMblk,
704  sizeof(M_BLK_ID), tick_timeout);
705  }
706 
707  if (bytesrx > 0)
708  {
709  bytesrx = (*pMblk)->mBlkHdr.mLen;
710  NIC_WVEVENT(ECAT_STACK_RECV, (char *)&bytesrx, sizeof(bytesrx));
711  }
712 
713 
714  return (bytesrx > 0);
715 }
716 
731 int ecx_inframe(ecx_portt *port, int idx, int stacknumber, int timeout)
732 {
733  uint16 l;
734  int rval;
735  ec_etherheadert *ehp;
736  ec_comt *ecp;
737  ec_stackT *stack;
738  ec_bufT *rxbuf;
739  ec_bufT *tempinbuf;
740  M_BLK_ID pMblk;
741 
742  if (!stacknumber)
743  {
744  stack = &(port->stack);
745  }
746  else
747  {
748  stack = &(port->redport->stack);
749  }
750  rval = EC_NOFRAME;
751  rxbuf = &(*stack->rxbuf)[idx];
752  /* (non-) blocking call to retrieve frame from Muxlayer */
753  if (ecx_recvpkt(port, idx, stacknumber, &pMblk, timeout))
754  {
755  rval = EC_OTHERFRAME;
756 
757  /* Get pointer to the frame */
758  tempinbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
759  /* Get pointer to the Ethernet header */
760  ehp = (ec_etherheadert*)tempinbuf;
761  /* Get pointer to the EtherCAT frame as ethernet payload */
762  ecp = (ec_comt*)&(*tempinbuf)[ETH_HEADERSIZE];
763  l = etohs(ecp->elength) & 0x0fff;
764  /* yes, put it in the buffer array (strip ethernet header) */
765  netMblkOffsetToBufCopy(pMblk, ETH_HEADERSIZE,(void *) rxbuf,
766  (*stack->txbuflength)[idx] - ETH_HEADERSIZE, NULL);
767 
768  /* return WKC */
769  rval = ((*rxbuf)[l] + ((uint16)((*rxbuf)[l + 1]) << 8));
770  /* mark as completed */
771  (*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
772  /* store MAC source word 1 for redundant routing info */
773  (*stack->rxsa)[idx] = ntohs(ehp->sa1);
774  netMblkClChainFree(pMblk);
775  port->pktDev.rx_count++;
776  }
777 
778  /* WKC if matching frame found */
779  return rval;
780 }
781 
795 static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer, int timeout)
796 {
797  osal_timert timer2;
798  int wkc = EC_NOFRAME;
799  int wkc2 = EC_NOFRAME;
800  int primrx, secrx;
801 
802  /* if not in redundant mode then always assume secondary is OK */
803  if (port->redstate == ECT_RED_NONE)
804  {
805  wkc2 = 0;
806  }
807  do
808  {
809  /* only read frame if not already in */
810  if (wkc <= EC_NOFRAME)
811  {
812  wkc = ecx_inframe(port, idx, 0, timeout);
813  }
814  /* only try secondary if in redundant mode */
815  if (port->redstate != ECT_RED_NONE)
816  {
817  /* only read frame if not already in */
818  if (wkc2 <= EC_NOFRAME)
819  {
820  wkc2 = ecx_inframe(port, idx, 1, timeout);
821  }
822  }
823  /* wait for both frames to arrive or timeout */
824  } while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
825  /* only do redundant functions when in redundant mode */
826  if (port->redstate != ECT_RED_NONE)
827  {
828  /* primrx if the received MAC source on primary socket */
829  primrx = 0;
830  if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
831  /* secrx if the received MAC source on psecondary socket */
832  secrx = 0;
833  if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
834 
835  /* primary socket got secondary frame and secondary socket got primary frame */
836  /* normal situation in redundant mode */
837  if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
838  {
839  /* copy secondary buffer to primary */
840  memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
841  wkc = wkc2;
842  }
843  /* primary socket got nothing or primary frame, and secondary socket got secondary frame */
844  /* we need to resend TX packet */
845  if ( ((primrx == 0) && (secrx == RX_SEC)) ||
846  ((primrx == RX_PRIM) && (secrx == RX_SEC)) )
847  {
848  /* If both primary and secondary have partial connection retransmit the primary received
849  * frame over the secondary socket. The result from the secondary received frame is a combined
850  * frame that traversed all slaves in standard order. */
851  if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
852  {
853  /* copy primary rx to tx buffer */
854  memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
855  }
856  osal_timer_start (&timer2, EC_TIMEOUTRET);
857  /* resend secondary tx */
858  ecx_outframe(port, idx, 1);
859  do
860  {
861  /* retrieve frame */
862  wkc2 = ecx_inframe(port, idx, 1, timeout);
863  } while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
864  if (wkc2 > EC_NOFRAME)
865  {
866  /* copy secondary result to primary rx buffer */
867  memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
868  wkc = wkc2;
869  }
870  }
871  }
872 
873  /* return WKC or EC_NOFRAME */
874  return wkc;
875 }
876 
884 int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
885 {
886  int wkc;
887  osal_timert timer;
888 
889  osal_timer_start (&timer, timeout);
890  wkc = ecx_waitinframe_red(port, idx, &timer, timeout);
891 
892  return wkc;
893 }
894 
907 int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
908 {
909  int wkc = EC_NOFRAME;
910  osal_timert timer1, timer2;
911 
912  osal_timer_start (&timer1, timeout);
913  do
914  {
915  /* tx frame on primary and if in redundant mode a dummy on secondary */
916  ecx_outframe_red(port, idx);
917  if (timeout < EC_TIMEOUTRET)
918  {
919  osal_timer_start (&timer2, timeout);
920  }
921  else
922  {
923  /* normally use partial timeout for rx */
924  osal_timer_start (&timer2, EC_TIMEOUTRET);
925  }
926  /* get frame from primary or if in redundant mode possibly from secondary */
927  wkc = ecx_waitinframe_red(port, idx, &timer2, timeout);
928  /* wait for answer with WKC>=0 or otherwise retry until timeout */
929  } while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
930 
931 
932  return wkc;
933 }
934 
935 #ifdef EC_VER1
936 int ec_setupnic(const char *ifname, int secondary)
937 {
938  return ecx_setupnic(&ecx_port, ifname, secondary);
939 }
940 
941 int ec_closenic(void)
942 {
943  return ecx_closenic(&ecx_port);
944 }
945 
946 int ec_getindex(void)
947 {
948  return ecx_getindex(&ecx_port);
949 }
950 
951 void ec_setbufstat(int idx, int bufstat)
952 {
953  ecx_setbufstat(&ecx_port, idx, bufstat);
954 }
955 
956 int ec_outframe(int idx, int stacknumber)
957 {
958  return ecx_outframe(&ecx_port, idx, stacknumber);
959 }
960 
961 int ec_outframe_red(int idx)
962 {
963  return ecx_outframe_red(&ecx_port, idx);
964 }
965 
966 int ec_inframe(int idx, int stacknumber, int timeout)
967 {
968  return ecx_inframe(&ecx_port, idx, stacknumber, timeout);
969 }
970 
971 int ec_waitinframe(int idx, int timeout)
972 {
973  return ecx_waitinframe(&ecx_port, idx, timeout);
974 }
975 
976 int ec_srconfirm(int idx, int timeout)
977 {
978  return ecx_srconfirm(&ecx_port, idx, timeout);
979 }
980 #endif
const uint16 secMAC[3]
int ec_outframe(int idx, int sock)
#define RX_SEC
static unsigned int usec_per_tick
ec_bufT rxbuf[EC_MAXBUF]
Definition: erika/nicdrv.h:43
int rxsa[EC_MAXBUF]
Definition: erika/nicdrv.h:47
Headerfile for nicdrv.c.
ec_bufT txbuf[EC_MAXBUF]
Definition: erika/nicdrv.h:68
boolean osal_timer_is_expired(osal_timert *self)
Definition: erika/osal.c:74
int(* rxsa)[EC_MAXBUF]
Definition: erika/nicdrv.h:34
int txbuflength[EC_MAXBUF]
Definition: erika/nicdrv.h:70
int ec_setupnic(const char *ifname, int secondary)
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer, int timeout)
static void ecx_clear_rxbufstat(int *rxbufstat)
#define EC_MAXBUF
Definition: ethercattype.h:62
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
void print_nicversion(void)
#define RX_PRIM
ec_bufT txbuf2
Definition: erika/nicdrv.h:72
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
int ecx_closenic(ecx_portt *port)
int rxsa[EC_MAXBUF]
Definition: erika/nicdrv.h:62
int ecx_outframe_red(ecx_portt *port, int idx)
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
const uint16 priMAC[3]
int(* txbuflength)[EC_MAXBUF]
Definition: erika/nicdrv.h:26
PACKED_BEGIN struct PACKED ec_etherheadert
static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID *pMblk, int timeout)
#define ECAT_RECV_OK
int txbuflength2
Definition: erika/nicdrv.h:74
uint16_t uint16
Definition: osal.h:29
#define etohs(A)
Definition: ethercattype.h:536
#define TRUE
Definition: osal.h:19
#define ETH_HEADERSIZE
Definition: ethercattype.h:103
int rxbufstat[EC_MAXBUF]
Definition: erika/nicdrv.h:45
ec_stackT stack
Definition: erika/nicdrv.h:55
ec_bufT rxbuf[EC_MAXBUF]
Definition: erika/nicdrv.h:58
ec_stackT stack
Definition: erika/nicdrv.h:40
ec_bufT(* rxbuf)[EC_MAXBUF]
Definition: erika/nicdrv.h:30
#define ECAT_SEND_FAILED
int ec_srconfirm(int idx, int timeout)
#define FALSE
Definition: osal.h:22
ec_bufT(* txbuf)[EC_MAXBUF]
Definition: erika/nicdrv.h:24
void ec_setbufstat(int idx, int bufstat)
void ec_setupheader(void *p)
int ecx_getindex(ecx_portt *port)
ecx_redportt * redport
Definition: erika/nicdrv.h:80
PACKED_BEGIN struct PACKED ec_comt
#define ECAT_RECV_FAILED
#define IF_NAME_SIZE
#define EC_TIMEOUTRET
Definition: ethercattype.h:64
#define EC_OTHERFRAME
Definition: ethercattype.h:43
#define NIC_WVEVENT(a, b, c)
int ec_outframe_red(int idx)
int redstate
Definition: erika/nicdrv.h:78
#define ETH_P_ECAT
Definition: ethercattype.h:459
int wkc
Definition: aliastool.c:47
int ecx_inframe(ecx_portt *port, int idx, int stacknumber, int timeout)
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
int rxbufstat[EC_MAXBUF]
Definition: erika/nicdrv.h:60
#define ECAT_RECV_RETRY_OK
uint8 ec_bufT[EC_BUFSIZE]
Definition: ethercattype.h:87
int ec_closenic(void)
Headerfile for oshw.c.
MSG_Q_ID msgQId[EC_MAXBUF]
int ec_getindex(void)
static int mux_rx_callback(void *pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg)
#define USECS_PER_SEC
#define ECAT_STACK_RECV
int ec_waitinframe(int idx, int timeout)
void osal_timer_start(osal_timert *self, uint32 timeout_usec)
Definition: erika/osal.c:59
int(* rxbufstat)[EC_MAXBUF]
Definition: erika/nicdrv.h:32
#define EC_NOFRAME
Definition: ethercattype.h:41
#define NIC_LOGMSG(x, a, b, c, d, e, f)
struct ecx_port * port
static int ec_outfram_send(ETHERCAT_PKT_DEV *pPktDev, int idx, void *buf, int len)
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
#define ECAT_SEND_COMPLETE
uint8 rxbuf[1024]
Definition: eoe_test.c:50


soem
Author(s): Arthur Ketels and M.J.G. van den Molengraft
autogenerated on Sat Jun 27 2020 03:48:21