ethercatmain.c
Go to the documentation of this file.
1 /*
2  * Simple Open EtherCAT Master Library
3  *
4  * File : ethercatmain.c
5  * Version : 1.3.0
6  * Date : 24-02-2013
7  * Copyright (C) 2005-2013 Speciaal Machinefabriek Ketels v.o.f.
8  * Copyright (C) 2005-2013 Arthur Ketels
9  * Copyright (C) 2008-2009 TU/e Technische Universiteit Eindhoven
10  *
11  * SOEM is free software; you can redistribute it and/or modify it under
12  * the terms of the GNU General Public License version 2 as published by the Free
13  * Software Foundation.
14  *
15  * SOEM is distributed in the hope that it will be useful, but WITHOUT ANY
16  * WARRANTY; without even the implied warranty of MERCHANTABILITY or
17  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
18  * for more details.
19  *
20  * As a special exception, if other files instantiate templates or use macros
21  * or inline functions from this file, or you compile this file and link it
22  * with other works to produce a work based on this file, this file does not
23  * by itself cause the resulting work to be covered by the GNU General Public
24  * License. However the source code for this file must still be made available
25  * in accordance with section (3) of the GNU General Public License.
26  *
27  * This exception does not invalidate any other reasons why a work based on
28  * this file might be covered by the GNU General Public License.
29  *
30  * The EtherCAT Technology, the trade name and logo EtherCAT are the intellectual
31  * property of, and protected by Beckhoff Automation GmbH. You can use SOEM for
32  * the sole purpose of creating, using and/or selling or otherwise distributing
33  * an EtherCAT network master provided that an EtherCAT Master License is obtained
34  * from Beckhoff Automation GmbH.
35  *
36  * In case you did not receive a copy of the EtherCAT Master License along with
37  * SOEM write to Beckhoff Automation GmbH, Eiserstraße 5, D-33415 Verl, Germany
38  * (www.beckhoff.com).
39  */
40 
53 #include <stdio.h>
54 #include <string.h>
55 #include "osal.h"
56 #include "oshw.h"
57 #include "ethercattype.h"
58 #include "ethercatbase.h"
59 #include "ethercatmain.h"
60 
61 
63 #define EC_LOCALDELAY 200
64 
66 PACKED_BEGIN
67 typedef struct PACKED
68 {
72 } ec_eepromt;
73 PACKED_END
74 
76 PACKED_BEGIN
77 typedef struct PACKED
78 {
82 } ec_mbxerrort;
83 PACKED_END
84 
86 PACKED_BEGIN
87 typedef struct PACKED
88 {
95 } ec_emcyt;
96 PACKED_END
97 
98 #ifdef EC_VER1
99 
104 ec_slavet ec_slave[EC_MAXSLAVE];
106 int ec_slavecount;
108 ec_groupt ec_group[EC_MAXGROUP];
109 
111 static uint8 esibuf[EC_MAXEEPBUF];
113 static uint32 esimap[EC_MAXEEPBITMAP];
115 static ec_eringt ec_elist;
116 static ec_idxstackT ec_idxstack;
117 
119 static ec_SMcommtypet ec_SMcommtype;
121 static ec_PDOassignt ec_PDOassign;
123 static ec_PDOdesct ec_PDOdesc;
124 
126 static ec_eepromSMt ec_SM;
128 static ec_eepromFMMUt ec_FMMU;
130 boolean EcatError = FALSE;
131 
132 int64 ec_DCtime;
133 
134 ecx_portt ecx_port;
135 ecx_redportt ecx_redport;
136 
137 ecx_contextt ecx_context = {
138  &ecx_port, // .port =
139  &ec_slave[0], // .slavelist =
140  &ec_slavecount, // .slavecount =
141  EC_MAXSLAVE, // .maxslave =
142  &ec_group[0], // .grouplist =
143  EC_MAXGROUP, // .maxgroup =
144  &esibuf[0], // .esibuf =
145  &esimap[0], // .esimap =
146  0, // .esislave =
147  &ec_elist, // .elist =
148  &ec_idxstack, // .idxstack =
149  &EcatError, // .ecaterror =
150  0, // .DCtO =
151  0, // .DCl =
152  &ec_DCtime, // .DCtime =
153  &ec_SMcommtype, // .SMcommtype =
154  &ec_PDOassign, // .PDOassign =
155  &ec_PDOdesc, // .PDOdesc =
156  &ec_SM, // .eepSM =
157  &ec_FMMU // .eepFMMU =
158 };
159 #endif
160 
166 {
167  ec_adaptert * ret_adapter;
168 
169  ret_adapter = oshw_find_adapters ();
170 
171  return ret_adapter;
172 }
173 
179 {
180  oshw_free_adapters (adapter);
181 }
182 
188 void ecx_pusherror(ecx_contextt *context, const ec_errort *Ec)
189 {
190  context->elist->Error[context->elist->head] = *Ec;
191  context->elist->Error[context->elist->head].Signal = TRUE;
192  context->elist->head++;
193  if (context->elist->head > EC_MAXELIST)
194  {
195  context->elist->head = 0;
196  }
197  if (context->elist->head == context->elist->tail)
198  {
199  context->elist->tail++;
200  }
201  if (context->elist->tail > EC_MAXELIST)
202  {
203  context->elist->tail = 0;
204  }
205  *(context->ecaterror) = TRUE;
206 }
207 
214 boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
215 {
216  boolean notEmpty = (context->elist->head != context->elist->tail);
217 
218  *Ec = context->elist->Error[context->elist->tail];
219  context->elist->Error[context->elist->tail].Signal = FALSE;
220  if (notEmpty)
221  {
222  context->elist->tail++;
223  if (context->elist->tail > EC_MAXELIST)
224  {
225  context->elist->tail = 0;
226  }
227  }
228  else
229  {
230  *(context->ecaterror) = FALSE;
231  }
232  return notEmpty;
233 }
234 
240 boolean ecx_iserror(ecx_contextt *context)
241 {
242  return (context->elist->head != context->elist->tail);
243 }
244 
254 {
255  ec_errort Ec;
256 
257  Ec.Time = osal_current_time();
258  Ec.Slave = Slave;
259  Ec.Index = Index;
260  Ec.SubIdx = SubIdx;
261  *(context->ecaterror) = TRUE;
263  Ec.ErrorCode = ErrorCode;
264  ecx_pusherror(context, &Ec);
265 }
266 
273 static void ecx_mbxerror(ecx_contextt *context, uint16 Slave,uint16 Detail)
274 {
275  ec_errort Ec;
276 
277  Ec.Time = osal_current_time();
278  Ec.Slave = Slave;
279  Ec.Index = 0;
280  Ec.SubIdx = 0;
282  Ec.ErrorCode = Detail;
283  ecx_pusherror(context, &Ec);
284 }
285 
297  uint8 b1, uint16 w1, uint16 w2)
298 {
299  ec_errort Ec;
300 
301  Ec.Time = osal_current_time();
302  Ec.Slave = Slave;
303  Ec.Index = 0;
304  Ec.SubIdx = 0;
306  Ec.ErrorCode = ErrorCode;
307  Ec.ErrorReg = (uint8)ErrorReg;
308  Ec.b1 = b1;
309  Ec.w1 = w1;
310  Ec.w2 = w2;
311  ecx_pusherror(context, &Ec);
312 }
313 
319 int ecx_init(ecx_contextt *context, char * ifname)
320 {
321  return ecx_setupnic(context->port, ifname, FALSE);
322 }
323 
331 int ecx_init_redundant(ecx_contextt *context, ecx_redportt *redport, char *ifname, char *if2name)
332 {
333  int rval, zbuf;
334  ec_etherheadert *ehp;
335 
336  context->port->redport = redport;
337  ecx_setupnic(context->port, ifname, FALSE);
338  rval = ecx_setupnic(context->port, if2name, TRUE);
339  /* prepare "dummy" BRD tx frame for redundant operation */
340  ehp = (ec_etherheadert *)&(context->port->txbuf2);
341  ehp->sa1 = oshw_htons(secMAC[0]);
342  zbuf = 0;
343  ecx_setupdatagram(context->port, &(context->port->txbuf2), EC_CMD_BRD, 0, 0x0000, 0x0000, 2, &zbuf);
345 
346  return rval;
347 }
348 
352 void ecx_close(ecx_contextt *context)
353 {
354  ecx_closenic(context->port);
355 };
356 
366 {
367  uint16 configadr, eadr;
368  uint64 edat;
369  uint16 mapw, mapb;
370  int lp,cnt;
371  uint8 retval;
372 
373  retval = 0xff;
374  if (slave != context->esislave) /* not the same slave? */
375  {
376  memset(context->esimap, 0x00, EC_MAXEEPBITMAP); /* clear esibuf cache map */
377  context->esislave = slave;
378  }
379  if (address < EC_MAXEEPBUF)
380  {
381  mapw = address >> 5;
382  mapb = address - (mapw << 5);
383  if (context->esimap[mapw] & (uint32)(1 << mapb))
384  {
385  /* byte is already in buffer */
386  retval = context->esibuf[address];
387  }
388  else
389  {
390  /* byte is not in buffer, put it there */
391  configadr = context->slavelist[slave].configadr;
392  ecx_eeprom2master(context, slave); /* set eeprom control to master */
393  eadr = address >> 1;
394  edat = ecx_readeepromFP (context, configadr, eadr, EC_TIMEOUTEEP);
395  /* 8 byte response */
396  if (context->slavelist[slave].eep_8byte)
397  {
398  put_unaligned64(edat, &(context->esibuf[eadr << 1]));
399  cnt = 8;
400  }
401  /* 4 byte response */
402  else
403  {
404  put_unaligned32(edat, &(context->esibuf[eadr << 1]));
405  cnt = 4;
406  }
407  /* find bitmap location */
408  mapw = eadr >> 4;
409  mapb = (eadr << 1) - (mapw << 5);
410  for(lp = 0 ; lp < cnt ; lp++)
411  {
412  /* set bitmap for each byte that is read */
413  context->esimap[mapw] |= (1 << mapb);
414  mapb++;
415  if (mapb > 31)
416  {
417  mapb = 0;
418  mapw++;
419  }
420  }
421  retval = context->esibuf[address];
422  }
423  }
424 
425  return retval;
426 }
427 
435 {
436  int16 a;
437  uint16 p;
438  uint8 eectl = context->slavelist[slave].eep_pdi;
439 
440  a = ECT_SII_START << 1;
441  /* read first SII section category */
442  p = ecx_siigetbyte(context, slave, a++);
443  p += (ecx_siigetbyte(context, slave, a++) << 8);
444  /* traverse SII while category is not found and not EOF */
445  while ((p != cat) && (p != 0xffff))
446  {
447  /* read section length */
448  p = ecx_siigetbyte(context, slave, a++);
449  p += (ecx_siigetbyte(context, slave, a++) << 8);
450  /* locate next section category */
451  a += p << 1;
452  /* read section category */
453  p = ecx_siigetbyte(context, slave, a++);
454  p += (ecx_siigetbyte(context, slave, a++) << 8);
455  }
456  if (p != cat)
457  {
458  a = 0;
459  }
460  if (eectl)
461  {
462  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
463  }
464 
465  return a;
466 }
467 
474 void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
475 {
476  uint16 a,i,j,l,n,ba;
477  char *ptr;
478  uint8 eectl = context->slavelist[slave].eep_pdi;
479 
480  ptr = str;
481  a = ecx_siifind (context, slave, ECT_SII_STRING); /* find string section */
482  if (a > 0)
483  {
484  ba = a + 2; /* skip SII section header */
485  n = ecx_siigetbyte(context, slave, ba++); /* read number of strings in section */
486  if (Sn <= n) /* is req string available? */
487  {
488  for (i = 1; i <= Sn; i++) /* walk through strings */
489  {
490  l = ecx_siigetbyte(context, slave, ba++); /* length of this string */
491  if (i < Sn)
492  {
493  ba += l;
494  }
495  else
496  {
497  ptr = str;
498  for (j = 1; j <= l; j++) /* copy one string */
499  {
500  if(j <= EC_MAXNAME)
501  {
502  *ptr = (char)ecx_siigetbyte(context, slave, ba++);
503  ptr++;
504  }
505  else
506  {
507  ba++;
508  }
509  }
510  }
511  }
512  *ptr = 0; /* add zero terminator */
513  }
514  else
515  {
516  ptr = str;
517  *ptr = 0; /* empty string */
518  }
519  }
520  if (eectl)
521  {
522  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
523  }
524 }
525 
533 {
534  uint16 a;
535  uint8 eectl = context->slavelist[slave].eep_pdi;
536 
537  FMMU->nFMMU = 0;
538  FMMU->FMMU0 = 0;
539  FMMU->FMMU1 = 0;
540  FMMU->FMMU2 = 0;
541  FMMU->FMMU3 = 0;
542  FMMU->Startpos = ecx_siifind(context, slave, ECT_SII_FMMU);
543 
544  if (FMMU->Startpos > 0)
545  {
546  a = FMMU->Startpos;
547  FMMU->nFMMU = ecx_siigetbyte(context, slave, a++);
548  FMMU->nFMMU += (ecx_siigetbyte(context, slave, a++) << 8);
549  FMMU->nFMMU *= 2;
550  FMMU->FMMU0 = ecx_siigetbyte(context, slave, a++);
551  FMMU->FMMU1 = ecx_siigetbyte(context, slave, a++);
552  if (FMMU->nFMMU > 2)
553  {
554  FMMU->FMMU2 = ecx_siigetbyte(context, slave, a++);
555  FMMU->FMMU3 = ecx_siigetbyte(context, slave, a++);
556  }
557  }
558  if (eectl)
559  {
560  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
561  }
562 
563  return FMMU->nFMMU;
564 }
565 
573 {
574  uint16 a,w;
575  uint8 eectl = context->slavelist[slave].eep_pdi;
576 
577  SM->nSM = 0;
578  SM->Startpos = ecx_siifind(context, slave, ECT_SII_SM);
579  if (SM->Startpos > 0)
580  {
581  a = SM->Startpos;
582  w = ecx_siigetbyte(context, slave, a++);
583  w += (ecx_siigetbyte(context, slave, a++) << 8);
584  SM->nSM = (w / 4);
585  SM->PhStart = ecx_siigetbyte(context, slave, a++);
586  SM->PhStart += (ecx_siigetbyte(context, slave, a++) << 8);
587  SM->Plength = ecx_siigetbyte(context, slave, a++);
588  SM->Plength += (ecx_siigetbyte(context, slave, a++) << 8);
589  SM->Creg = ecx_siigetbyte(context, slave, a++);
590  SM->Sreg = ecx_siigetbyte(context, slave, a++);
591  SM->Activate = ecx_siigetbyte(context, slave, a++);
592  SM->PDIctrl = ecx_siigetbyte(context, slave, a++);
593  }
594  if (eectl)
595  {
596  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
597  }
598 
599  return SM->nSM;
600 }
601 
610 {
611  uint16 a;
612  uint16 retVal = 0;
613  uint8 eectl = context->slavelist[slave].eep_pdi;
614 
615  if (n < SM->nSM)
616  {
617  a = SM->Startpos + 2 + (n * 8);
618  SM->PhStart = ecx_siigetbyte(context, slave, a++);
619  SM->PhStart += (ecx_siigetbyte(context, slave, a++) << 8);
620  SM->Plength = ecx_siigetbyte(context, slave, a++);
621  SM->Plength += (ecx_siigetbyte(context, slave, a++) << 8);
622  SM->Creg = ecx_siigetbyte(context, slave, a++);
623  SM->Sreg = ecx_siigetbyte(context, slave, a++);
624  SM->Activate = ecx_siigetbyte(context, slave, a++);
625  SM->PDIctrl = ecx_siigetbyte(context, slave, a++);
626  retVal = 1;
627  }
628  if (eectl)
629  {
630  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
631  }
632 
633  return retVal;
634 }
635 
644 {
645  uint16 a , w, c, e, er, Size;
646  uint8 eectl = context->slavelist[slave].eep_pdi;
647 
648  Size = 0;
649  PDO->nPDO = 0;
650  PDO->Length = 0;
651  PDO->Index[1] = 0;
652  for (c = 0 ; c < EC_MAXSM ; c++) PDO->SMbitsize[c] = 0;
653  if (t > 1)
654  t = 1;
655  PDO->Startpos = ecx_siifind(context, slave, ECT_SII_PDO + t);
656  if (PDO->Startpos > 0)
657  {
658  a = PDO->Startpos;
659  w = ecx_siigetbyte(context, slave, a++);
660  w += (ecx_siigetbyte(context, slave, a++) << 8);
661  PDO->Length = w;
662  c = 1;
663  /* traverse through all PDOs */
664  do
665  {
666  PDO->nPDO++;
667  PDO->Index[PDO->nPDO] = ecx_siigetbyte(context, slave, a++);
668  PDO->Index[PDO->nPDO] += (ecx_siigetbyte(context, slave, a++) << 8);
669  PDO->BitSize[PDO->nPDO] = 0;
670  c++;
671  e = ecx_siigetbyte(context, slave, a++);
672  PDO->SyncM[PDO->nPDO] = ecx_siigetbyte(context, slave, a++);
673  a += 4;
674  c += 2;
675  if (PDO->SyncM[PDO->nPDO] < EC_MAXSM) /* active and in range SM? */
676  {
677  /* read all entries defined in PDO */
678  for (er = 1; er <= e; er++)
679  {
680  c += 4;
681  a += 5;
682  PDO->BitSize[PDO->nPDO] += ecx_siigetbyte(context, slave, a++);
683  a += 2;
684  }
685  PDO->SMbitsize[ PDO->SyncM[PDO->nPDO] ] += PDO->BitSize[PDO->nPDO];
686  Size += PDO->BitSize[PDO->nPDO];
687  c++;
688  }
689  else /* PDO deactivated because SM is 0xff or > EC_MAXSM */
690  {
691  c += 4 * e;
692  a += 8 * e;
693  c++;
694  }
695  if (PDO->nPDO >= (EC_MAXEEPDO - 1))
696  {
697  c = PDO->Length; /* limit number of PDO entries in buffer */
698  }
699  }
700  while (c < PDO->Length);
701  }
702  if (eectl)
703  {
704  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
705  }
706 
707  return (Size);
708 }
709 
715 {
716  uint16 slave, configadr, lowest, rval;
717  ec_alstatust slstat;
718 
719  lowest = 0xff;
720  context->slavelist[0].ALstatuscode = 0;
721  for (slave = 1; slave <= *(context->slavecount); slave++)
722  {
723  configadr = context->slavelist[slave].configadr;
724  slstat.alstatus = 0;
725  slstat.alstatuscode = 0;
726  ecx_FPRD(context->port, configadr, ECT_REG_ALSTAT, sizeof(slstat), &slstat, EC_TIMEOUTRET3);
727  rval = etohs(slstat.alstatus);
728  context->slavelist[slave].ALstatuscode = etohs(slstat.alstatuscode);
729  if (rval < lowest)
730  {
731  lowest = rval;
732  }
733  context->slavelist[slave].state = rval;
734  context->slavelist[0].ALstatuscode |= context->slavelist[slave].ALstatuscode;
735  }
736  context->slavelist[0].state = lowest;
737 
738  return lowest;
739 }
740 
747 int ecx_writestate(ecx_contextt *context, uint16 slave)
748 {
749  uint16 configadr, slstate;
750 
751  if (slave == 0)
752  {
753  slstate = htoes(context->slavelist[slave].state);
754  ecx_BWR(context->port, 0, ECT_REG_ALCTL, sizeof(slstate), &slstate, EC_TIMEOUTRET3); /* write slave status */
755  }
756  else
757  {
758  configadr = context->slavelist[slave].configadr;
759 
760  ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(context->slavelist[slave].state), EC_TIMEOUTRET3); /* write slave status */
761  }
762  return 0;
763 }
764 
773 uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
774 {
775  uint16 configadr, state, rval;
776  ec_alstatust slstat;
777  osal_timert timer;
778 
779  if ( slave > *(context->slavecount) )
780  {
781  return 0;
782  }
783  osal_timer_start(&timer, timeout);
784  configadr = context->slavelist[slave].configadr;
785  do
786  {
787  if (slave < 1)
788  {
789  rval = 0;
790  ecx_BRD(context->port, 0, ECT_REG_ALSTAT, sizeof(rval), &rval , EC_TIMEOUTRET);
791  rval = etohs(rval);
792  }
793  else
794  {
795  slstat.alstatus = 0;
796  slstat.alstatuscode = 0;
797  ecx_FPRD(context->port, configadr, ECT_REG_ALSTAT, sizeof(slstat), &slstat, EC_TIMEOUTRET);
798  rval = etohs(slstat.alstatus);
799  context->slavelist[slave].ALstatuscode = etohs(slstat.alstatuscode);
800  }
801  state = rval & 0x000f; /* read slave status */
802  if (state != reqstate)
803  {
804  osal_usleep(1000);
805  }
806  }
807  while ((state != reqstate) && (osal_timer_is_expired(&timer) == FALSE));
808  context->slavelist[slave].state = rval;
809 
810  return state;
811 }
812 
819 {
820  cnt++;
821  if (cnt > 7)
822  {
823  cnt = 1; /* wrap around to 1, not 0 */
824  }
825 
826  return cnt;
827 }
828 
833 {
834  memset(*Mbx, 0x00, EC_MAXMBX);
835 }
836 
843 int ecx_mbxempty(ecx_contextt *context, uint16 slave, int timeout)
844 {
845  uint16 configadr;
846  uint8 SMstat;
847  int wkc;
848  osal_timert timer;
849 
850  osal_timer_start(&timer, timeout);
851  configadr = context->slavelist[slave].configadr;
852  do
853  {
854  wkc = ecx_FPRD(context->port, configadr, ECT_REG_SM0STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
855  SMstat = etohs(SMstat);
856  if (((SMstat & 0x08) != 0) && (timeout > EC_LOCALDELAY))
857  {
859  }
860  }
861  while (((wkc <= 0) || ((SMstat & 0x08) != 0)) && (osal_timer_is_expired(&timer) == FALSE));
862 
863  if ((wkc > 0) && ((SMstat & 0x08) == 0))
864  {
865  return 1;
866  }
867 
868  return 0;
869 }
870 
878 int ecx_mbxsend(ecx_contextt *context, uint16 slave,ec_mbxbuft *mbx, int timeout)
879 {
880  uint16 mbxwo,mbxl,configadr;
881  int wkc;
882 
883  wkc = 0;
884  configadr = context->slavelist[slave].configadr;
885  mbxl = context->slavelist[slave].mbx_l;
886  if (mbxl > 0)
887  {
888  if (ecx_mbxempty(context, slave, timeout))
889  {
890  mbxwo = context->slavelist[slave].mbx_wo;
891  /* write slave in mailbox */
892  wkc = ecx_FPWR(context->port, configadr, mbxwo, mbxl, mbx, EC_TIMEOUTRET3);
893  }
894  else
895  {
896  wkc = 0;
897  }
898  }
899 
900  return wkc;
901 }
902 
911 int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
912 {
913  uint16 mbxro,mbxl,configadr;
914  int wkc=0;
915  int wkc2;
916  uint16 SMstat;
917  uint8 SMcontr;
918  ec_mbxheadert *mbxh;
919  ec_emcyt *EMp;
920  ec_mbxerrort *MBXEp;
921 
922  configadr = context->slavelist[slave].configadr;
923  mbxl = context->slavelist[slave].mbx_rl;
924  if (mbxl > 0)
925  {
926  osal_timert timer;
927 
928  osal_timer_start(&timer, timeout);
929  wkc = 0;
930  do /* wait for read mailbox available */
931  {
932  wkc = ecx_FPRD(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
933  SMstat = etohs(SMstat);
934  if (((SMstat & 0x08) == 0) && (timeout > EC_LOCALDELAY))
935  {
937  }
938  }
939  while (((wkc <= 0) || ((SMstat & 0x08) == 0)) && (osal_timer_is_expired(&timer) == FALSE));
940 
941  if ((wkc > 0) && ((SMstat & 0x08) > 0)) /* read mailbox available ? */
942  {
943  mbxro = context->slavelist[slave].mbx_ro;
944  mbxh = (ec_mbxheadert *)mbx;
945  do
946  {
947  wkc = ecx_FPRD(context->port, configadr, mbxro, mbxl, mbx, EC_TIMEOUTRET); /* get mailbox */
948 
949 // // EtherCAT slaves of KUKA youBot don't send standard mailbox header as reply,
950 // // so don't check for error codes here
951 //
952 // if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == 0x00)) /* Mailbox error response? */
953 // {
954 // MBXEp = (ec_mbxerrort *)mbx;
955 // ecx_mbxerror(context, slave, etohs(MBXEp->Detail));
956 // wkc = 0; /* prevent emergency to cascade up, it is already handled. */
957 // }
958 // else if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == 0x03)) /* CoE response? */
959 // {
960 // EMp = (ec_emcyt *)mbx;
961 // if ((etohs(EMp->CANOpen) >> 12) == 0x01) /* Emergency request? */
962 // {
963 // ecx_mbxemergencyerror(context, slave, etohs(EMp->ErrorCode), EMp->ErrorReg,
964 // EMp->bData, etohs(EMp->w1), etohs(EMp->w2));
965 // wkc = 0; /* prevent emergency to cascade up, it is already handled. */
966 // }
967 // }
968 // else
969  {
970  if (wkc <= 0) /* read mailbox lost */
971  {
972  SMstat ^= 0x0200; /* toggle repeat request */
973  SMstat = htoes(SMstat);
974  wkc2 = ecx_FPWR(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
975  SMstat = etohs(SMstat);
976  do /* wait for toggle ack */
977  {
978  wkc2 = ecx_FPRD(context->port, configadr, ECT_REG_SM1CONTR, sizeof(SMcontr), &SMcontr, EC_TIMEOUTRET);
979  } while (((wkc2 <= 0) || ((SMcontr & 0x02) != (HI_BYTE(SMstat) & 0x02))) && (osal_timer_is_expired(&timer) == FALSE));
980  do /* wait for read mailbox available */
981  {
982  wkc2 = ecx_FPRD(context->port, configadr, ECT_REG_SM1STAT, sizeof(SMstat), &SMstat, EC_TIMEOUTRET);
983  SMstat = etohs(SMstat);
984  if (((SMstat & 0x08) == 0) && (timeout > EC_LOCALDELAY))
985  {
987  }
988  } while (((wkc2 <= 0) || ((SMstat & 0x08) == 0)) && (osal_timer_is_expired(&timer) == FALSE));
989  }
990  }
991  } while ((wkc <= 0) && (osal_timer_is_expired(&timer) == FALSE)); /* if WKC<=0 repeat */
992  }
993  else /* no read mailbox available */
994  {
995  wkc = 0;
996  }
997  }
998 
999  return wkc;
1000 }
1001 
1007 void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf)
1008 {
1009  int address, incr;
1010  uint16 configadr;
1011  uint64 *p64;
1012  uint16 *p16;
1013  uint64 edat;
1014  uint8 eectl = context->slavelist[slave].eep_pdi;
1015 
1016  ecx_eeprom2master(context, slave); /* set eeprom control to master */
1017  configadr = context->slavelist[slave].configadr;
1018  address = ECT_SII_START;
1019  p16=(uint16*)esibuf;
1020  if (context->slavelist[slave].eep_8byte)
1021  {
1022  incr = 4;
1023  }
1024  else
1025  {
1026  incr = 2;
1027  }
1028  do
1029  {
1030  edat = ecx_readeepromFP(context, configadr, address, EC_TIMEOUTEEP);
1031  p64 = (uint64*)p16;
1032  *p64 = edat;
1033  p16 += incr;
1034  address += incr;
1035  } while ((address <= (EC_MAXEEPBUF >> 1)) && ((uint32)edat != 0xffffffff));
1036 
1037  if (eectl)
1038  {
1039  ecx_eeprom2pdi(context, slave); /* if eeprom control was previously pdi then restore */
1040  }
1041 }
1042 
1050 uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
1051 {
1052  uint16 configadr;
1053 
1054  ecx_eeprom2master(context, slave); /* set eeprom control to master */
1055  configadr = context->slavelist[slave].configadr;
1056 
1057  return ((uint32)ecx_readeepromFP(context, configadr, eeproma, timeout));
1058 }
1059 
1068 int ecx_writeeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout)
1069 {
1070  uint16 configadr;
1071 
1072  ecx_eeprom2master(context, slave); /* set eeprom control to master */
1073  configadr = context->slavelist[slave].configadr;
1074  return (ecx_writeeepromFP(context, configadr, eeproma, data, timeout));
1075 }
1076 
1083 {
1084  int wkc = 1, cnt = 0;
1085  uint16 configadr;
1086  uint8 eepctl;
1087 
1088  if ( context->slavelist[slave].eep_pdi )
1089  {
1090  configadr = context->slavelist[slave].configadr;
1091  eepctl = 2;
1092  do
1093  {
1094  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* force Eeprom from PDI */
1095  }
1096  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1097  eepctl = 0;
1098  cnt = 0;
1099  do
1100  {
1101  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* set Eeprom to master */
1102  }
1103  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1104  context->slavelist[slave].eep_pdi = 0;
1105  }
1106 
1107  return wkc;
1108 }
1109 
1115 int ecx_eeprom2pdi(ecx_contextt *context, uint16 slave)
1116 {
1117  int wkc = 1, cnt = 0;
1118  uint16 configadr;
1119  uint8 eepctl;
1120 
1121  if ( !context->slavelist[slave].eep_pdi )
1122  {
1123  configadr = context->slavelist[slave].configadr;
1124  eepctl = 1;
1125  do
1126  {
1127  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* set Eeprom to PDI */
1128  }
1129  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1130  context->slavelist[slave].eep_pdi = 1;
1131  }
1132 
1133  return wkc;
1134 }
1135 
1136 uint16 ecx_eeprom_waitnotbusyAP(ecx_contextt *context, uint16 aiadr,uint16 *estat, int timeout)
1137 {
1138  int wkc, cnt = 0, retval = 0;
1139  osal_timert timer;
1140 
1141  osal_timer_start(&timer, timeout);
1142  do
1143  {
1144  if (cnt++)
1145  {
1147  }
1148  wkc=ecx_APRD(context->port, aiadr, ECT_REG_EEPSTAT, sizeof(*estat), estat, EC_TIMEOUTRET);
1149  *estat = etohs(*estat);
1150  }
1151  while (((wkc <= 0) || ((*estat & EC_ESTAT_BUSY) > 0)) && (osal_timer_is_expired(&timer) == FALSE)); /* wait for eeprom ready */
1152  if ((*estat & EC_ESTAT_BUSY) == 0)
1153  {
1154  retval = 1;
1155  }
1156 
1157  return retval;
1158 }
1159 
1167 uint64 ecx_readeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout)
1168 {
1169  uint16 estat;
1170  uint32 edat32;
1171  uint64 edat64;
1172  ec_eepromt ed;
1173  int wkc, cnt, nackcnt = 0;
1174 
1175  edat64 = 0;
1176  edat32 = 0;
1177  if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
1178  {
1179  if (estat & EC_ESTAT_EMASK) /* error bits are set */
1180  {
1181  estat = htoes(EC_ECMD_NOP); /* clear error bits */
1182  wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
1183  }
1184 
1185  do
1186  {
1187  ed.comm = htoes(EC_ECMD_READ);
1188  ed.addr = htoes(eeproma);
1189  ed.d2 = 0x0000;
1190  cnt = 0;
1191  do
1192  {
1193  wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
1194  }
1195  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1196  if (wkc)
1197  {
1199  estat = 0x0000;
1200  if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
1201  {
1202  if (estat & EC_ESTAT_NACK)
1203  {
1204  nackcnt++;
1206  }
1207  else
1208  {
1209  nackcnt = 0;
1210  if (estat & EC_ESTAT_R64)
1211  {
1212  cnt = 0;
1213  do
1214  {
1215  wkc = ecx_APRD(context->port, aiadr, ECT_REG_EEPDAT, sizeof(edat64), &edat64, EC_TIMEOUTRET);
1216  }
1217  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1218  }
1219  else
1220  {
1221  cnt = 0;
1222  do
1223  {
1224  wkc = ecx_APRD(context->port, aiadr, ECT_REG_EEPDAT, sizeof(edat32), &edat32, EC_TIMEOUTRET);
1225  }
1226  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1227  edat64=(uint64)edat32;
1228  }
1229  }
1230  }
1231  }
1232  }
1233  while ((nackcnt > 0) && (nackcnt < 3));
1234  }
1235 
1236  return edat64;
1237 }
1238 
1247 int ecx_writeeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
1248 {
1249  uint16 estat;
1250  ec_eepromt ed;
1251  int wkc, rval = 0, cnt = 0, nackcnt = 0;
1252 
1253  if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
1254  {
1255  if (estat & EC_ESTAT_EMASK) /* error bits are set */
1256  {
1257  estat = htoes(EC_ECMD_NOP); /* clear error bits */
1258  wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
1259  }
1260  do
1261  {
1262  cnt = 0;
1263  do
1264  {
1265  wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPDAT, sizeof(data), &data, EC_TIMEOUTRET);
1266  }
1267  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1268 
1269  ed.comm = EC_ECMD_WRITE;
1270  ed.addr = eeproma;
1271  ed.d2 = 0x0000;
1272  cnt = 0;
1273  do
1274  {
1275  wkc = ecx_APWR(context->port, aiadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
1276  }
1277  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1278  if (wkc)
1279  {
1281  estat = 0x0000;
1282  if (ecx_eeprom_waitnotbusyAP(context, aiadr, &estat, timeout))
1283  {
1284  if (estat & EC_ESTAT_NACK)
1285  {
1286  nackcnt++;
1288  }
1289  else
1290  {
1291  nackcnt = 0;
1292  rval = 1;
1293  }
1294  }
1295  }
1296 
1297  }
1298  while ((nackcnt > 0) && (nackcnt < 3));
1299  }
1300 
1301  return rval;
1302 }
1303 
1304 uint16 ecx_eeprom_waitnotbusyFP(ecx_contextt *context, uint16 configadr,uint16 *estat, int timeout)
1305 {
1306  int wkc, cnt = 0, retval = 0;
1307  osal_timert timer;
1308 
1309  osal_timer_start(&timer, timeout);
1310  do
1311  {
1312  if (cnt++)
1313  {
1315  }
1316  wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPSTAT, sizeof(*estat), estat, EC_TIMEOUTRET);
1317  *estat = etohs(*estat);
1318  }
1319  while (((wkc <= 0) || ((*estat & EC_ESTAT_BUSY) > 0)) && (osal_timer_is_expired(&timer) == FALSE)); /* wait for eeprom ready */
1320  if ((*estat & EC_ESTAT_BUSY) == 0)
1321  {
1322  retval = 1;
1323  }
1324 
1325  return retval;
1326 }
1327 
1335 uint64 ecx_readeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout)
1336 {
1337  uint16 estat;
1338  uint32 edat32;
1339  uint64 edat64;
1340  ec_eepromt ed;
1341  int wkc, cnt, nackcnt = 0;
1342 
1343  edat64 = 0;
1344  edat32 = 0;
1345  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
1346  {
1347  if (estat & EC_ESTAT_EMASK) /* error bits are set */
1348  {
1349  estat = htoes(EC_ECMD_NOP); /* clear error bits */
1350  wkc=ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
1351  }
1352 
1353  do
1354  {
1355  ed.comm = htoes(EC_ECMD_READ);
1356  ed.addr = htoes(eeproma);
1357  ed.d2 = 0x0000;
1358  cnt = 0;
1359  do
1360  {
1361  wkc=ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
1362  }
1363  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1364  if (wkc)
1365  {
1367  estat = 0x0000;
1368  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
1369  {
1370  if (estat & EC_ESTAT_NACK)
1371  {
1372  nackcnt++;
1374  }
1375  else
1376  {
1377  nackcnt = 0;
1378  if (estat & EC_ESTAT_R64)
1379  {
1380  cnt = 0;
1381  do
1382  {
1383  wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat64), &edat64, EC_TIMEOUTRET);
1384  }
1385  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1386  }
1387  else
1388  {
1389  cnt = 0;
1390  do
1391  {
1392  wkc=ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat32), &edat32, EC_TIMEOUTRET);
1393  }
1394  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1395  edat64=(uint64)edat32;
1396  }
1397  }
1398  }
1399  }
1400  }
1401  while ((nackcnt > 0) && (nackcnt < 3));
1402  }
1403 
1404  return edat64;
1405 }
1406 
1415 int ecx_writeeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout)
1416 {
1417  uint16 estat;
1418  ec_eepromt ed;
1419  int wkc, rval = 0, cnt = 0, nackcnt = 0;
1420 
1421  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
1422  {
1423  if (estat & EC_ESTAT_EMASK) /* error bits are set */
1424  {
1425  estat = htoes(EC_ECMD_NOP); /* clear error bits */
1426  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
1427  }
1428  do
1429  {
1430  cnt = 0;
1431  do
1432  {
1433  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPDAT, sizeof(data), &data, EC_TIMEOUTRET);
1434  }
1435  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1436  ed.comm = EC_ECMD_WRITE;
1437  ed.addr = eeproma;
1438  ed.d2 = 0x0000;
1439  cnt = 0;
1440  do
1441  {
1442  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
1443  }
1444  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1445  if (wkc)
1446  {
1448  estat = 0x0000;
1449  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
1450  {
1451  if (estat & EC_ESTAT_NACK)
1452  {
1453  nackcnt++;
1455  }
1456  else
1457  {
1458  nackcnt = 0;
1459  rval = 1;
1460  }
1461  }
1462  }
1463  }
1464  while ((nackcnt > 0) && (nackcnt < 3));
1465  }
1466 
1467  return rval;
1468 }
1469 
1476 void ecx_readeeprom1(ecx_contextt *context, uint16 slave, uint16 eeproma)
1477 {
1478  uint16 configadr, estat;
1479  ec_eepromt ed;
1480  int wkc, cnt = 0;
1481 
1482  ecx_eeprom2master(context, slave); /* set eeprom control to master */
1483  configadr = context->slavelist[slave].configadr;
1484  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, EC_TIMEOUTEEP))
1485  {
1486  if (estat & EC_ESTAT_EMASK) /* error bits are set */
1487  {
1488  estat = htoes(EC_ECMD_NOP); /* clear error bits */
1489  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(estat), &estat, EC_TIMEOUTRET3);
1490  }
1491  ed.comm = htoes(EC_ECMD_READ);
1492  ed.addr = htoes(eeproma);
1493  ed.d2 = 0x0000;
1494  do
1495  {
1496  wkc = ecx_FPWR(context->port, configadr, ECT_REG_EEPCTL, sizeof(ed), &ed, EC_TIMEOUTRET);
1497  }
1498  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1499  }
1500 }
1501 
1509 uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout)
1510 {
1511  uint16 estat, configadr;
1512  uint32 edat;
1513  int wkc, cnt = 0;
1514 
1515  configadr = context->slavelist[slave].configadr;
1516  edat = 0;
1517  estat = 0x0000;
1518  if (ecx_eeprom_waitnotbusyFP(context, configadr, &estat, timeout))
1519  {
1520  do
1521  {
1522  wkc = ecx_FPRD(context->port, configadr, ECT_REG_EEPDAT, sizeof(edat), &edat, EC_TIMEOUTRET);
1523  }
1524  while ((wkc <= 0) && (cnt++ < EC_DEFAULTRETRIES));
1525  }
1526 
1527  return edat;
1528 }
1529 
1536 static void ecx_pushindex(ecx_contextt *context, uint8 idx, void *data, uint16 length)
1537 {
1538  if(context->idxstack->pushed < EC_MAXBUF)
1539  {
1540  context->idxstack->idx[context->idxstack->pushed] = idx;
1541  context->idxstack->data[context->idxstack->pushed] = data;
1542  context->idxstack->length[context->idxstack->pushed] = length;
1543  context->idxstack->pushed++;
1544  }
1545 }
1546 
1551 static int ecx_pullindex(ecx_contextt *context)
1552 {
1553  int rval = -1;
1554  if(context->idxstack->pulled < context->idxstack->pushed)
1555  {
1556  rval = context->idxstack->pulled;
1557  context->idxstack->pulled++;
1558  }
1559 
1560  return rval;
1561 }
1562 
1576 {
1577  uint32 LogAdr;
1578  uint16 w1, w2;
1579  int length, sublength;
1580  uint8 idx;
1581  int wkc;
1582  uint8* data;
1583  boolean first=FALSE;
1584  uint16 currentsegment = 0;
1585 
1586  wkc = 0;
1587  if(context->grouplist[group].hasdc)
1588  {
1589  first = TRUE;
1590  }
1591  length = context->grouplist[group].Obytes + context->grouplist[group].Ibytes;
1592  LogAdr = context->grouplist[group].logstartaddr;
1593  if (length)
1594  {
1595  if(!group)
1596  {
1597  context->idxstack->pushed = 0;
1598  context->idxstack->pulled = 0;
1599  }
1600  wkc = 1;
1601  /* LRW blocked by one or more slaves ? */
1602  if (context->grouplist[group].blockLRW)
1603  {
1604  /* if inputs available generate LRD */
1605  if(context->grouplist[group].Ibytes)
1606  {
1607  currentsegment = context->grouplist[group].Isegment;
1608  data = context->grouplist[group].inputs;
1609  length = context->grouplist[group].Ibytes;
1610  LogAdr += context->grouplist[group].Obytes;
1611  /* segment transfer if needed */
1612  do
1613  {
1614  if(currentsegment == context->grouplist[group].Isegment)
1615  {
1616  sublength = context->grouplist[group].IOsegment[currentsegment++] - context->grouplist[group].Ioffset;
1617  }
1618  else
1619  {
1620  sublength = context->grouplist[group].IOsegment[currentsegment++];
1621  }
1622  /* get new index */
1623  idx = ecx_getindex(context->port);
1624  w1 = LO_WORD(LogAdr);
1625  w2 = HI_WORD(LogAdr);
1626  ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRD, idx, w1, w2, sublength, data);
1627  if(first)
1628  {
1629  context->DCl = sublength;
1630  /* FPRMW in second datagram */
1631  context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
1632  context->slavelist[context->grouplist[group].DCnext].configadr,
1633  ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
1634  first = FALSE;
1635  }
1636  /* send frame */
1637  ecx_outframe_red(context->port, idx);
1638  /* push index and data pointer on stack */
1639  ecx_pushindex(context, idx, data, sublength);
1640  length -= sublength;
1641  LogAdr += sublength;
1642  data += sublength;
1643  } while (length && (currentsegment < context->grouplist[group].nsegments));
1644  }
1645  /* if outputs available generate LWR */
1646  if(context->grouplist[group].Obytes)
1647  {
1648  data = context->grouplist[group].outputs;
1649  length = context->grouplist[group].Obytes;
1650  LogAdr = context->grouplist[group].logstartaddr;
1651  currentsegment = 0;
1652  /* segment transfer if needed */
1653  do
1654  {
1655  sublength = context->grouplist[group].IOsegment[currentsegment++];
1656  if((length - sublength) < 0)
1657  {
1658  sublength = length;
1659  }
1660  /* get new index */
1661  idx = ecx_getindex(context->port);
1662  w1 = LO_WORD(LogAdr);
1663  w2 = HI_WORD(LogAdr);
1664  ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LWR, idx, w1, w2, sublength, data);
1665  if(first)
1666  {
1667  context->DCl = sublength;
1668  /* FPRMW in second datagram */
1669  context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
1670  context->slavelist[context->grouplist[group].DCnext].configadr,
1671  ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
1672  first = FALSE;
1673  }
1674  /* send frame */
1675  ecx_outframe_red(context->port, idx);
1676  /* push index and data pointer on stack */
1677  ecx_pushindex(context, idx, data, sublength);
1678  length -= sublength;
1679  LogAdr += sublength;
1680  data += sublength;
1681  } while (length && (currentsegment < context->grouplist[group].nsegments));
1682  }
1683  }
1684  /* LRW can be used */
1685  else
1686  {
1687  if (context->grouplist[group].Obytes)
1688  {
1689  data = context->grouplist[group].outputs;
1690  }
1691  else
1692  {
1693  data = context->grouplist[group].inputs;
1694  }
1695  /* segment transfer if needed */
1696  do
1697  {
1698  sublength = context->grouplist[group].IOsegment[currentsegment++];
1699  /* get new index */
1700  idx = ecx_getindex(context->port);
1701  w1 = LO_WORD(LogAdr);
1702  w2 = HI_WORD(LogAdr);
1703  ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRW, idx, w1, w2, sublength, data);
1704  if(first)
1705  {
1706  context->DCl = sublength;
1707  /* FPRMW in second datagram */
1708  context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
1709  context->slavelist[context->grouplist[group].DCnext].configadr,
1710  ECT_REG_DCSYSTIME, sizeof(context->DCtime), context->DCtime);
1711  first = FALSE;
1712  }
1713  /* send frame */
1714  ecx_outframe_red(context->port, idx);
1715  /* push index and data pointer on stack */
1716  ecx_pushindex(context, idx, data, sublength);
1717  length -= sublength;
1718  LogAdr += sublength;
1719  data += sublength;
1720  } while (length && (currentsegment < context->grouplist[group].nsegments));
1721  }
1722  }
1723 
1724  return wkc;
1725 }
1726 
1736 int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeout)
1737 {
1738  int pos, idx;
1739  int wkc = 0, wkc2;
1740  uint16 le_wkc = 0;
1741  int64 le_DCtime;
1742  boolean first = FALSE;
1743 
1744  if(context->grouplist[group].hasdc)
1745  {
1746  first = TRUE;
1747  }
1748  /* get first index */
1749  pos = ecx_pullindex(context);
1750  /* read the same number of frames as send */
1751  while (pos >= 0)
1752  {
1753  idx = context->idxstack->idx[pos];
1754  wkc2 = ecx_waitinframe(context->port, context->idxstack->idx[pos], timeout);
1755  /* check if there is input data in frame */
1756  if (wkc2 > EC_NOFRAME)
1757  {
1758  if((context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRD) || (context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRW))
1759  {
1760  if(first)
1761  {
1762  memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->DCl);
1763  memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
1764  wkc = etohs(le_wkc);
1765  memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
1766  *(context->DCtime) = etohll(le_DCtime);
1767  first = FALSE;
1768  }
1769  else
1770  {
1771  /* copy input data back to process data buffer */
1772  memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->idxstack->length[pos]);
1773  wkc += wkc2;
1774  }
1775  }
1776  else if(context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LWR)
1777  {
1778  if(first)
1779  {
1780  memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
1781  /* output WKC counts 2 times when using LRW, emulate the same for LWR */
1782  wkc = etohs(le_wkc) * 2;
1783  memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
1784  *(context->DCtime) = etohll(le_DCtime);
1785  first = FALSE;
1786  }
1787  else
1788  {
1789  /* output WKC counts 2 times when using LRW, emulate the same for LWR */
1790  wkc += wkc2 * 2;
1791  }
1792  }
1793  }
1794  /* release buffer */
1795  ecx_setbufstat(context->port, idx, EC_BUF_EMPTY);
1796  /* get next index */
1797  pos = ecx_pullindex(context);
1798  }
1799 
1800  return wkc;
1801 }
1802 
1803 
1805 {
1806  return ecx_send_processdata_group(context, 0);
1807 }
1808 
1809 int ecx_receive_processdata(ecx_contextt *context, int timeout)
1810 {
1811  return ecx_receive_processdata_group(context, 0, timeout);
1812 }
1813 
1814 #ifdef EC_VER1
1815 void ec_pusherror(const ec_errort *Ec)
1816 {
1817  ecx_pusherror(&ecx_context, Ec);
1818 }
1819 
1820 boolean ec_poperror(ec_errort *Ec)
1821 {
1822  return ecx_poperror(&ecx_context, Ec);
1823 }
1824 
1825 boolean ec_iserror(void)
1826 {
1827  return ecx_iserror(&ecx_context);
1828 }
1829 
1830 void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
1831 {
1832  ecx_packeterror(&ecx_context, Slave, Index, SubIdx, ErrorCode);
1833 }
1834 
1835 static void ec_mbxerror(uint16 Slave,uint16 Detail)
1836 {
1837  ecx_mbxerror (&ecx_context, Slave, Detail);
1838 }
1839 
1840 static void ec_mbxemergencyerror(uint16 Slave,uint16 ErrorCode,uint16 ErrorReg,
1841  uint8 b1, uint16 w1, uint16 w2)
1842 {
1843  ecx_mbxemergencyerror (&ecx_context, Slave, ErrorCode, ErrorReg, b1, w1, w2);
1844 }
1845 
1846 int ec_init(char * ifname)
1847 {
1848  return ecx_init(&ecx_context, ifname);
1849 }
1850 
1851 int ec_init_redundant(char *ifname, char *if2name)
1852 {
1853  return ecx_init_redundant (&ecx_context, &ecx_redport, ifname, if2name);
1854 }
1855 
1856 void ec_close(void)
1857 {
1858  ecx_close(&ecx_context);
1859 };
1860 
1861 uint8 ec_siigetbyte(uint16 slave, uint16 address)
1862 {
1863  return ecx_siigetbyte (&ecx_context, slave, address);
1864 }
1865 
1866 int16 ec_siifind(uint16 slave, uint16 cat)
1867 {
1868  return ecx_siifind (&ecx_context, slave, cat);
1869 }
1870 
1871 void ec_siistring(char *str, uint16 slave, uint16 Sn)
1872 {
1873  ecx_siistring(&ecx_context, str, slave, Sn);
1874 }
1875 
1876 uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU)
1877 {
1878  return ecx_siiFMMU (&ecx_context, slave, FMMU);
1879 }
1880 
1881 uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM)
1882 {
1883  return ecx_siiSM (&ecx_context, slave, SM);
1884 }
1885 
1886 uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n)
1887 {
1888  return ecx_siiSMnext (&ecx_context, slave, SM, n);
1889 }
1890 
1891 int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t)
1892 {
1893  return ecx_siiPDO (&ecx_context, slave, PDO, t);
1894 }
1895 
1896 int ec_readstate(void)
1897 {
1898  return ecx_readstate (&ecx_context);
1899 }
1900 
1901 int ec_writestate(uint16 slave)
1902 {
1903  return ecx_writestate(&ecx_context, slave);
1904 }
1905 
1906 uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout)
1907 {
1908  return ecx_statecheck (&ecx_context, slave, reqstate, timeout);
1909 }
1910 
1911 int ec_mbxempty(uint16 slave, int timeout)
1912 {
1913  return ecx_mbxempty (&ecx_context, slave, timeout);
1914 }
1915 
1916 int ec_mbxsend(uint16 slave,ec_mbxbuft *mbx, int timeout)
1917 {
1918  return ecx_mbxsend (&ecx_context, slave, mbx, timeout);
1919 }
1920 
1921 int ec_mbxreceive(uint16 slave, ec_mbxbuft *mbx, int timeout)
1922 {
1923  return ecx_mbxreceive (&ecx_context, slave, mbx, timeout);
1924 }
1925 
1926 void ec_esidump(uint16 slave, uint8 *esibuf)
1927 {
1928  ecx_esidump (&ecx_context, slave, esibuf);
1929 }
1930 
1931 uint32 ec_readeeprom(uint16 slave, uint16 eeproma, int timeout)
1932 {
1933  return ecx_readeeprom (&ecx_context, slave, eeproma, timeout);
1934 }
1935 
1936 int ec_writeeeprom(uint16 slave, uint16 eeproma, uint16 data, int timeout)
1937 {
1938  return ecx_writeeeprom (&ecx_context, slave, eeproma, data, timeout);
1939 }
1940 
1941 int ec_eeprom2master(uint16 slave)
1942 {
1943  return ecx_eeprom2master(&ecx_context, slave);
1944 }
1945 
1946 int ec_eeprom2pdi(uint16 slave)
1947 {
1948  return ecx_eeprom2pdi(&ecx_context, slave);
1949 }
1950 
1951 uint16 ec_eeprom_waitnotbusyAP(uint16 aiadr,uint16 *estat, int timeout)
1952 {
1953  return ecx_eeprom_waitnotbusyAP (&ecx_context, aiadr, estat, timeout);
1954 }
1955 
1956 uint64 ec_readeepromAP(uint16 aiadr, uint16 eeproma, int timeout)
1957 {
1958  return ecx_readeepromAP (&ecx_context, aiadr, eeproma, timeout);
1959 }
1960 
1961 int ec_writeeepromAP(uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
1962 {
1963  return ecx_writeeepromAP (&ecx_context, aiadr, eeproma, data, timeout);
1964 }
1965 
1966 uint16 ec_eeprom_waitnotbusyFP(uint16 configadr,uint16 *estat, int timeout)
1967 {
1968  return ecx_eeprom_waitnotbusyFP (&ecx_context, configadr, estat, timeout);
1969 }
1970 
1971 uint64 ec_readeepromFP(uint16 configadr, uint16 eeproma, int timeout)
1972 {
1973  return ecx_readeepromFP (&ecx_context, configadr, eeproma, timeout);
1974 }
1975 
1976 int ec_writeeepromFP(uint16 configadr, uint16 eeproma, uint16 data, int timeout)
1977 {
1978  return ecx_writeeepromFP (&ecx_context, configadr, eeproma, data, timeout);
1979 }
1980 
1981 void ec_readeeprom1(uint16 slave, uint16 eeproma)
1982 {
1983  ecx_readeeprom1 (&ecx_context, slave, eeproma);
1984 }
1985 
1986 uint32 ec_readeeprom2(uint16 slave, int timeout)
1987 {
1988  return ecx_readeeprom2 (&ecx_context, slave, timeout);
1989 }
1990 
1991 int ec_send_processdata_group(uint8 group)
1992 {
1993  return ecx_send_processdata_group (&ecx_context, group);
1994 }
1995 
1996 int ec_receive_processdata_group(uint8 group, int timeout)
1997 {
1998  return ecx_receive_processdata_group (&ecx_context, group, timeout);
1999 }
2000 
2001 int ec_send_processdata(void)
2002 {
2003  return ec_send_processdata_group(0);
2004 }
2005 
2006 int ec_receive_processdata(int timeout)
2007 {
2008  return ec_receive_processdata_group(0, timeout);
2009 }
2010 #endif
int ecx_send_processdata(ecx_contextt *context)
uint16 ErrorCode
Definition: ethercatmain.c:91
PACKED_END ec_adaptert * ec_find_adapters(void)
Definition: ethercatmain.c:165
uint16 mbx_rl
Definition: ethercatmain.h:192
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:409
int ecx_mbxempty(ecx_contextt *context, uint16 slave, int timeout)
Definition: ethercatmain.c:843
#define EC_MAXMBX
Definition: ethercatmain.h:66
uint16 BitSize[EC_MAXEEPDO]
Definition: ethercatmain.h:336
#define EC_ESTAT_NACK
Definition: ethercattype.h:299
uint8 eep_pdi
Definition: ethercatmain.h:242
uint16 Ioffset
Definition: ethercatmain.h:293
uint8 ErrorReg
Definition: ethercatmain.c:92
ec_bufT txbuf[EC_MAXBUF]
Definition: linux/nicdrv.h:106
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
Definition: linux/nicdrv.c:278
uint16 Plength
Definition: ethercatmain.h:321
ec_slavet * slavelist
Definition: ethercatmain.h:418
uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address)
Definition: ethercatmain.c:365
#define EC_MAXGROUP
Definition: ethercatmain.h:62
void ec_free_adapters(ec_adaptert *adapter)
Definition: ethercatmain.c:178
int ecx_APWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:372
uint16 comm
Definition: ethercatmain.c:69
uint16 d2
Definition: ethercatmain.c:71
int ecx_init(ecx_contextt *context, char *ifname)
Definition: ethercatmain.c:319
int16 head
Definition: ethercatmain.h:377
void ecx_close(ecx_contextt *context)
Definition: ethercatmain.c:352
ec_groupt * grouplist
Definition: ethercatmain.h:424
#define EC_MAXBUF
Definition: ethercattype.h:88
uint8_t uint8
Definition: osal.h:33
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
Definition: ethercatmain.c:773
int ecx_BWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:168
void ecx_pusherror(ecx_contextt *context, const ec_errort *Ec)
Definition: ethercatmain.c:188
uint16 mbx_l
Definition: ethercatmain.h:188
ec_bufT txbuf2
Definition: linux/nicdrv.h:110
#define EC_MAXEEPBUF
Definition: ethercattype.h:106
int ecx_BRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:195
uint32 Obytes
Definition: ethercatmain.h:273
PACKED_BEGIN struct PACKED ec_etherheadert
uint16 Startpos
Definition: ethercatmain.h:318
uint8 SubIdx
Definition: ethercattype.h:503
uint16 w2
Definition: ethercattype.h:517
void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
Definition: ethercatmain.c:474
uint8 idx[EC_MAXBUF]
Definition: ethercatmain.h:369
int txbuflength2
Definition: linux/nicdrv.h:112
uint16_t uint16
Definition: osal.h:34
uint16 DCnext
Definition: ethercatmain.h:283
#define EC_MAXEEPBITMAP
Definition: ethercattype.h:104
PACKED_BEGIN struct PACKED ec_eepromt
void ecx_packeterror(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
Definition: ethercatmain.c:253
uint16 SyncM[EC_MAXEEPDO]
Definition: ethercatmain.h:335
uint32 PDO[256]
Definition: ethercatmain.h:408
int ecx_eeprom2master(ecx_contextt *context, uint16 slave)
boolean osal_timer_is_expired(osal_timert *self)
Definition: linux/osal.c:78
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
Definition: linux/nicdrv.c:564
General typedefs and defines for EtherCAT.
#define EC_MAXEEPDO
Definition: ethercatmain.h:68
#define etohs(A)
Definition: ethercattype.h:550
uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt *FMMU)
Definition: ethercatmain.c:532
#define TRUE
Definition: osal.h:28
uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
#define ETH_HEADERSIZE
Definition: ethercattype.h:127
ec_err_type Etype
Definition: ethercattype.h:505
void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf)
void ec_clearmbx(ec_mbxbuft *Mbx)
Definition: ethercatmain.c:832
int ecx_closenic(ecx_portt *port)
Definition: linux/nicdrv.c:207
int ecx_APRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:227
static void ecx_mbxerror(ecx_contextt *context, uint16 Slave, uint16 Detail)
Definition: ethercatmain.c:273
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
Definition: linux/nicdrv.c:116
#define HI_BYTE(w)
Definition: ethercattype.h:526
#define EC_ESTAT_BUSY
Definition: ethercattype.h:295
#define EC_MAXSM
Definition: ethercatmain.h:70
uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt *SM, uint16 n)
Definition: ethercatmain.c:609
int ecx_outframe_red(ecx_portt *port, int idx)
Definition: linux/nicdrv.c:316
ec_timet osal_current_time(void)
Definition: linux/osal.c:52
boolean * ecaterror
Definition: ethercatmain.h:438
ec_bufT rxbuf[EC_MAXBUF]
Definition: linux/nicdrv.h:96
int ecx_writeeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout)
int ecx_mbxsend(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
Definition: ethercatmain.c:878
uint16 ALstatuscode
Definition: ethercatmain.h:142
int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data)
Definition: ethercatbase.c:113
PACKED_END PACKED_BEGIN struct PACKED ec_PDOassignt
PACKED_END PACKED_BEGIN struct PACKED ec_mbxerrort
static void ecx_mbxemergencyerror(ecx_contextt *context, uint16 Slave, uint16 ErrorCode, uint16 ErrorReg, uint8 b1, uint16 w1, uint16 w2)
Definition: ethercatmain.c:296
PACKED_BEGIN struct PACKED ec_mbxheadert
uint32 IOsegment[EC_MAXIOSEGMENTS]
Definition: ethercatmain.h:301
int ecx_writeeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
#define put_unaligned32(val, ptr)
Definition: ethercattype.h:539
uint8 n
Definition: ethercatmain.h:386
uint16 mbx_ro
Definition: ethercatmain.h:194
const uint16 secMAC[3]
Definition: linux/nicdrv.c:103
uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout)
#define EC_HEADERSIZE
Definition: ethercattype.h:151
uint16 SMbitsize[EC_MAXSM]
Definition: ethercatmain.h:337
boolean hasdc
Definition: ethercatmain.h:281
void oshw_free_adapters(ec_adaptert *adapter)
Definition: linux/oshw.c:121
int ecx_writeeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout)
uint16 Slave
Definition: ethercattype.h:499
uint64 ecx_readeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout)
ec_mbxheadert MbxHeader
Definition: ethercatcoe.c:61
uint16 Index
Definition: ethercatcoe.c:64
int ecx_writestate(ecx_contextt *context, uint16 slave)
Definition: ethercatmain.c:747
PACKED_END PACKED_BEGIN struct PACKED ec_emcyt
int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
Definition: ethercatmain.c:911
int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeout)
int64_t int64
Definition: osal.h:36
#define FALSE
Definition: osal.h:29
int osal_usleep(uint32 usec)
Definition: linux/osal.c:28
ec_errort Error[EC_MAXELIST+1]
Definition: ethercatmain.h:379
uint16 CANOpen
Definition: ethercatcoe.c:62
uint16 Isegment
Definition: ethercatmain.h:291
ecx_portt * port
Definition: ethercatmain.h:416
ecx_redportt * redport
Definition: linux/nicdrv.h:118
int64 * DCtime
Definition: ethercatmain.h:444
ec_idxstackT * idxstack
Definition: ethercatmain.h:436
#define ECT_SII_START
Definition: ethercattype.h:304
#define EC_TIMEOUTEEP
Definition: ethercattype.h:96
#define EC_CMDOFFSET
Definition: ethercattype.h:155
#define EC_MAXELIST
Definition: ethercatmain.h:56
boolean Signal
Definition: ethercattype.h:497
PACKED_END PACKED_BEGIN struct PACKED ec_PDOdesct
uint64_t uint64
Definition: osal.h:37
int ecx_send_processdata_group(ecx_contextt *context, uint8 group)
#define HI_WORD(l)
Definition: ethercattype.h:534
void osal_timer_start(osal_timert *self, uint32 timeout_us)
Definition: linux/osal.c:63
uint8 eep_8byte
Definition: ethercatmain.h:240
void ecx_readeeprom1(ecx_contextt *context, uint16 slave, uint16 eeproma)
uint16 esislave
Definition: ethercatmain.h:432
ec_eringt * elist
Definition: ethercatmain.h:434
uint64 ecx_readeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout)
int ecx_init_redundant(ecx_contextt *context, ecx_redportt *redport, char *ifname, char *if2name)
Definition: ethercatmain.c:331
#define EC_TIMEOUTRET
Definition: ethercattype.h:90
#define LO_WORD(l)
Definition: ethercattype.h:532
uint16 length[EC_MAXBUF]
Definition: ethercatmain.h:371
ec_timet Time
Definition: ethercattype.h:495
boolean ecx_iserror(ecx_contextt *context)
Definition: ethercatmain.c:240
uint16 ErrorCode
Definition: ethercattype.h:513
int ecx_setupdatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, uint16 ADP, uint16 ADO, uint16 length, void *data)
Definition: ethercatbase.c:72
Headerfile for ethercatbase.c.
#define EC_MAXSLAVE
Definition: ethercatmain.h:60
uint16 length
Definition: ethercatmain.h:347
#define htoes(A)
Definition: ethercattype.h:547
#define EC_MAXNAME
Definition: ethercatmain.h:58
#define EC_DEFAULTRETRIES
Definition: ethercattype.h:108
int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt *PDO, uint8 t)
Definition: ethercatmain.c:643
int ecx_eeprom2pdi(ecx_contextt *context, uint16 slave)
uint16 Index
Definition: ethercattype.h:501
uint32 logstartaddr
Definition: ethercatmain.h:271
uint32 ErrorCode
Definition: ethercatfoe.c:74
#define etohll(A)
Definition: ethercattype.h:552
uint16 mbx_wo
Definition: ethercatmain.h:190
Headerfile for ethercatmain.c.
boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
Definition: ethercatmain.c:214
uint8 blockLRW
Definition: ethercatmain.h:287
uint16 Detail
Definition: ethercatmain.c:81
uint16 w2
Definition: ethercatmain.c:94
#define EC_LOCALDELAY
Definition: ethercatmain.c:63
static int ecx_pullindex(ecx_contextt *context)
int16 tail
Definition: ethercatmain.h:378
uint32_t uint32
Definition: osal.h:35
#define EC_TIMEOUTRET3
Definition: ethercattype.h:92
uint16 addr
Definition: ethercatmain.c:70
uint16 address
Definition: ethercatmain.h:348
int ecx_FPWRw(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 data, int timeout)
Definition: ethercatbase.c:431
int ecx_readstate(ecx_contextt *context)
Definition: ethercatmain.c:714
uint32 * esimap
Definition: ethercatmain.h:430
ec_adaptert * oshw_find_adapters(void)
Definition: linux/oshw.c:57
uint32 Ibytes
Definition: ethercatmain.h:277
int16_t int16
Definition: osal.h:31
int16 ecx_siifind(ecx_contextt *context, uint16 slave, uint16 cat)
Definition: ethercatmain.c:434
uint16 state
Definition: ethercatmain.h:140
uint16 Type
Definition: ethercatmain.c:80
static void ecx_pushindex(ecx_contextt *context, uint8 idx, void *data, uint16 length)
uint8 * inputs
Definition: ethercatmain.h:279
#define EC_NOFRAME
Definition: ethercattype.h:73
int ecx_receive_processdata(ecx_contextt *context, int timeout)
Length
uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt *SM)
Definition: ethercatmain.c:572
uint16 PhStart
Definition: ethercatmain.h:320
uint16 w1
Definition: ethercattype.h:516
uint8 bData
Definition: ethercatmain.c:93
uint16 Index[EC_MAXEEPDO]
Definition: ethercatmain.h:334
PACKED_END PACKED_BEGIN struct PACKED ec_alstatust
uint16 ecx_eeprom_waitnotbusyFP(ecx_contextt *context, uint16 configadr, uint16 *estat, int timeout)
uint8 * outputs
Definition: ethercatmain.h:275
uint16 oshw_htons(uint16 hostshort)
Definition: linux/oshw.c:36
uint16 configadr
Definition: ethercatmain.h:144
int ecx_FPRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
Definition: ethercatbase.c:328
#define EC_ESTAT_EMASK
Definition: ethercattype.h:297
void * data[EC_MAXBUF]
Definition: ethercatmain.h:370
#define EC_ESTAT_R64
Definition: ethercattype.h:293
uint8 ErrorReg
Definition: ethercattype.h:514
#define EC_WKCSIZE
Definition: ethercattype.h:157
uint8 * esibuf
Definition: ethercatmain.h:428
PACKED_BEGIN struct PACKED ec_SMcommtypet
int ecx_getindex(ecx_portt *port)
Definition: linux/nicdrv.c:239
uint16 w1
Definition: ethercatmain.c:94
uint8 ec_mbxbuft[EC_MAXMBX+1]
Definition: ethercatmain.h:341
int * slavecount
Definition: ethercatmain.h:420
uint8 ec_nextmbxcnt(uint8 cnt)
Definition: ethercatmain.c:818
#define put_unaligned64(val, ptr)
Definition: ethercattype.h:542
uint16 ecx_eeprom_waitnotbusyAP(ecx_contextt *context, uint16 aiadr, uint16 *estat, int timeout)


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:24