Classes | Macros | Typedefs | Functions | Variables
ethercatmain.c File Reference

Main EtherCAT functions. More...

#include <stdio.h>
#include <string.h>
#include "osal.h"
#include "oshw.h"
#include "ethercat.h"
Include dependency graph for ethercatmain.c:

Go to the source code of this file.

Classes

struct  PACKED
 
struct  PACKED
 
struct  PACKED
 

Macros

#define EC_LOCALDELAY   200
 
#define MAX_FPRD_MULTI   64
 

Typedefs

typedef PACKED_BEGIN struct PACKED ec_eepromt
 
typedef PACKED_END PACKED_BEGIN struct PACKED ec_emcyt
 
typedef PACKED_END PACKED_BEGIN struct PACKED ec_mbxerrort
 

Functions

void ec_clearmbx (ec_mbxbuft *Mbx)
 
void ec_close (void)
 
int ec_eeprom2master (uint16 slave)
 
int ec_eeprom2pdi (uint16 slave)
 
uint16 ec_eeprom_waitnotbusyAP (uint16 aiadr, uint16 *estat, int timeout)
 
uint16 ec_eeprom_waitnotbusyFP (uint16 configadr, uint16 *estat, int timeout)
 
void ec_esidump (uint16 slave, uint8 *esibuf)
 
ec_adaptertec_find_adapters (void)
 
void ec_free_adapters (ec_adaptert *adapter)
 
int ec_init (const char *ifname)
 
int ec_init_redundant (const char *ifname, char *if2name)
 
boolean ec_iserror (void)
 
int ec_mbxempty (uint16 slave, int timeout)
 
int ec_mbxreceive (uint16 slave, ec_mbxbuft *mbx, int timeout)
 
int ec_mbxsend (uint16 slave, ec_mbxbuft *mbx, int timeout)
 
uint8 ec_nextmbxcnt (uint8 cnt)
 
void ec_packeterror (uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
 
boolean ec_poperror (ec_errort *Ec)
 
void ec_pusherror (const ec_errort *Ec)
 
uint32 ec_readeeprom (uint16 slave, uint16 eeproma, int timeout)
 
void ec_readeeprom1 (uint16 slave, uint16 eeproma)
 
uint32 ec_readeeprom2 (uint16 slave, int timeout)
 
uint64 ec_readeepromAP (uint16 aiadr, uint16 eeproma, int timeout)
 
uint64 ec_readeepromFP (uint16 configadr, uint16 eeproma, int timeout)
 
int ec_readstate (void)
 
int ec_receive_processdata (int timeout)
 
int ec_receive_processdata_group (uint8 group, int timeout)
 
int ec_send_overlap_processdata (void)
 
int ec_send_overlap_processdata_group (uint8 group)
 
int ec_send_processdata (void)
 
int ec_send_processdata_group (uint8 group)
 
int16 ec_siifind (uint16 slave, uint16 cat)
 
uint16 ec_siiFMMU (uint16 slave, ec_eepromFMMUt *FMMU)
 
uint8 ec_siigetbyte (uint16 slave, uint16 address)
 
int ec_siiPDO (uint16 slave, ec_eepromPDOt *PDO, uint8 t)
 
uint16 ec_siiSM (uint16 slave, ec_eepromSMt *SM)
 
uint16 ec_siiSMnext (uint16 slave, ec_eepromSMt *SM, uint16 n)
 
void ec_siistring (char *str, uint16 slave, uint16 Sn)
 
uint16 ec_statecheck (uint16 slave, uint16 reqstate, int timeout)
 
int ec_writeeeprom (uint16 slave, uint16 eeproma, uint16 data, int timeout)
 
int ec_writeeepromAP (uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
 
int ec_writeeepromFP (uint16 configadr, uint16 eeproma, uint16 data, int timeout)
 
int ec_writestate (uint16 slave)
 
static void ecx_clearindex (ecx_contextt *context)
 
void ecx_close (ecx_contextt *context)
 
int ecx_eeprom2master (ecx_contextt *context, uint16 slave)
 
int ecx_eeprom2pdi (ecx_contextt *context, uint16 slave)
 
uint16 ecx_eeprom_waitnotbusyAP (ecx_contextt *context, uint16 aiadr, uint16 *estat, int timeout)
 
uint16 ecx_eeprom_waitnotbusyFP (ecx_contextt *context, uint16 configadr, uint16 *estat, int timeout)
 
void ecx_esidump (ecx_contextt *context, uint16 slave, uint8 *esibuf)
 
int ecx_FPRD_multi (ecx_contextt *context, int n, uint16 *configlst, ec_alstatust *slstatlst, int timeout)
 
int ecx_init (ecx_contextt *context, const char *ifname)
 
int ecx_init_redundant (ecx_contextt *context, ecx_redportt *redport, const char *ifname, char *if2name)
 
boolean ecx_iserror (ecx_contextt *context)
 
static int ecx_main_send_processdata (ecx_contextt *context, uint8 group, boolean use_overlap_io)
 
static void ecx_mbxemergencyerror (ecx_contextt *context, uint16 Slave, uint16 ErrorCode, uint16 ErrorReg, uint8 b1, uint16 w1, uint16 w2)
 
int ecx_mbxempty (ecx_contextt *context, uint16 slave, int timeout)
 
static void ecx_mbxerror (ecx_contextt *context, uint16 Slave, uint16 Detail)
 
int ecx_mbxreceive (ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
 
int ecx_mbxsend (ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout)
 
void ecx_packeterror (ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
 
boolean ecx_poperror (ecx_contextt *context, ec_errort *Ec)
 
static int ecx_pullindex (ecx_contextt *context)
 
void ecx_pusherror (ecx_contextt *context, const ec_errort *Ec)
 
static void ecx_pushindex (ecx_contextt *context, uint8 idx, void *data, uint16 length)
 
uint32 ecx_readeeprom (ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
 
void ecx_readeeprom1 (ecx_contextt *context, uint16 slave, uint16 eeproma)
 
uint32 ecx_readeeprom2 (ecx_contextt *context, uint16 slave, int timeout)
 
uint64 ecx_readeepromAP (ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout)
 
uint64 ecx_readeepromFP (ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout)
 
int ecx_readstate (ecx_contextt *context)
 
int ecx_receive_processdata (ecx_contextt *context, int timeout)
 
int ecx_receive_processdata_group (ecx_contextt *context, uint8 group, int timeout)
 
int ecx_send_overlap_processdata (ecx_contextt *context)
 
int ecx_send_overlap_processdata_group (ecx_contextt *context, uint8 group)
 
int ecx_send_processdata (ecx_contextt *context)
 
int ecx_send_processdata_group (ecx_contextt *context, uint8 group)
 
int16 ecx_siifind (ecx_contextt *context, uint16 slave, uint16 cat)
 
uint16 ecx_siiFMMU (ecx_contextt *context, uint16 slave, ec_eepromFMMUt *FMMU)
 
uint8 ecx_siigetbyte (ecx_contextt *context, uint16 slave, uint16 address)
 
int ecx_siiPDO (ecx_contextt *context, uint16 slave, ec_eepromPDOt *PDO, uint8 t)
 
uint16 ecx_siiSM (ecx_contextt *context, uint16 slave, ec_eepromSMt *SM)
 
uint16 ecx_siiSMnext (ecx_contextt *context, uint16 slave, ec_eepromSMt *SM, uint16 n)
 
void ecx_siistring (ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
 
uint16 ecx_statecheck (ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
 
int ecx_writeeeprom (ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout)
 
int ecx_writeeepromAP (ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
 
int ecx_writeeepromFP (ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout)
 
int ecx_writestate (ecx_contextt *context, uint16 slave)
 

Variables

int64 ec_DCtime
 
static ec_eringt ec_elist
 
static uint8 ec_esibuf [EC_MAXEEPBUF]
 
static uint32 ec_esimap [EC_MAXEEPBITMAP]
 
static ec_eepromFMMUt ec_FMMU
 
ec_groupt ec_group [EC_MAXGROUP]
 
static ec_idxstackT ec_idxstack
 
static ec_PDOassignt ec_PDOassign [EC_MAX_MAPT]
 
static ec_PDOdesct ec_PDOdesc [EC_MAX_MAPT]
 
PACKED_END ec_slavet ec_slave [EC_MAXSLAVE]
 
int ec_slavecount
 
static ec_eepromSMt ec_SM
 
static ec_SMcommtypet ec_SMcommtype [EC_MAX_MAPT]
 
boolean EcatError = FALSE
 
ecx_contextt ecx_context
 
ecx_portt ecx_port
 
ecx_redportt ecx_redport
 

Detailed Description

Main EtherCAT functions.

Initialisation, state set and read, mailbox primitives, EEPROM primitives, SII reading and processdata exchange.

Defines ec_slave[]. All slave information is put in this structure. Needed for most user interaction with slaves.

Definition in file ethercatmain.c.

Macro Definition Documentation

◆ EC_LOCALDELAY

#define EC_LOCALDELAY   200

delay in us for eeprom ready loop

Definition at line 26 of file ethercatmain.c.

◆ MAX_FPRD_MULTI

#define MAX_FPRD_MULTI   64

Definition at line 681 of file ethercatmain.c.

Typedef Documentation

◆ ec_eepromt

typedef PACKED_BEGIN struct PACKED ec_eepromt

record for ethercat eeprom communications

◆ ec_emcyt

emergency request structure

◆ ec_mbxerrort

mailbox error structure

Function Documentation

◆ ec_clearmbx()

void ec_clearmbx ( ec_mbxbuft Mbx)

Clear mailbox buffer.

Parameters
[out]Mbx= Mailbox buffer to clear

Definition at line 921 of file ethercatmain.c.

◆ ec_close()

void ec_close ( void  )

Close lib.

See also
ecx_close

Definition at line 2048 of file ethercatmain.c.

◆ ec_eeprom2master()

int ec_eeprom2master ( uint16  slave)

Set eeprom control to master. Only if set to PDI.

Parameters
[in]slave= Slave number
Returns
>0 if OK
See also
ecx_eeprom2master

Definition at line 2243 of file ethercatmain.c.

◆ ec_eeprom2pdi()

int ec_eeprom2pdi ( uint16  slave)

Definition at line 2248 of file ethercatmain.c.

◆ ec_eeprom_waitnotbusyAP()

uint16 ec_eeprom_waitnotbusyAP ( uint16  aiadr,
uint16 estat,
int  timeout 
)

Definition at line 2253 of file ethercatmain.c.

◆ ec_eeprom_waitnotbusyFP()

uint16 ec_eeprom_waitnotbusyFP ( uint16  configadr,
uint16 estat,
int  timeout 
)

Definition at line 2282 of file ethercatmain.c.

◆ ec_esidump()

void ec_esidump ( uint16  slave,
uint8 esibuf 
)

Dump complete EEPROM data from slave in buffer.

Parameters
[in]slave= Slave number
[out]esibuf= EEPROM data buffer, make sure it is big enough.
See also
ecx_esidump

Definition at line 2208 of file ethercatmain.c.

◆ ec_find_adapters()

ec_adaptert* ec_find_adapters ( void  )

Create list over available network adapters.

Returns
First element in list over available network adapters.

Definition at line 131 of file ethercatmain.c.

◆ ec_free_adapters()

void ec_free_adapters ( ec_adaptert adapter)

Free dynamically allocated list over available network adapters.

Parameters
[in]adapter= Struct holding adapter name, description and pointer to next.

Definition at line 144 of file ethercatmain.c.

◆ ec_init()

int ec_init ( const char *  ifname)

Initialise lib in single NIC mode

Parameters
[in]ifname= Dev name, f.e. "eth0"
Returns
>0 if OK
See also
ecx_init

Definition at line 2029 of file ethercatmain.c.

◆ ec_init_redundant()

int ec_init_redundant ( const char *  ifname,
char *  if2name 
)

Initialise lib in redundant NIC mode

Parameters
[in]ifname= Primary Dev name, f.e. "eth0"
[in]if2name= Secondary Dev name, f.e. "eth1"
Returns
>0 if OK
See also
ecx_init_redundant

Definition at line 2040 of file ethercatmain.c.

◆ ec_iserror()

boolean ec_iserror ( void  )

Definition at line 2014 of file ethercatmain.c.

◆ ec_mbxempty()

int ec_mbxempty ( uint16  slave,
int  timeout 
)

Check if IN mailbox of slave is empty.

Parameters
[in]slave= Slave number
[in]timeout= Timeout in us
Returns
>0 is success
See also
ecx_mbxempty

Definition at line 2173 of file ethercatmain.c.

◆ ec_mbxreceive()

int ec_mbxreceive ( uint16  slave,
ec_mbxbuft mbx,
int  timeout 
)

Read OUT mailbox from slave. Supports Mailbox Link Layer with repeat requests.

Parameters
[in]slave= Slave number
[out]mbx= Mailbox data
[in]timeout= Timeout in us
Returns
Work counter (>0 is success)
See also
ecx_mbxreceive

Definition at line 2198 of file ethercatmain.c.

◆ ec_mbxsend()

int ec_mbxsend ( uint16  slave,
ec_mbxbuft mbx,
int  timeout 
)

Write IN mailbox to slave.

Parameters
[in]slave= Slave number
[out]mbx= Mailbox data
[in]timeout= Timeout in us
Returns
Work counter (>0 is success)
See also
ecx_mbxsend

Definition at line 2185 of file ethercatmain.c.

◆ ec_nextmbxcnt()

uint8 ec_nextmbxcnt ( uint8  cnt)

Get index of next mailbox counter value. Used for Mailbox Link Layer.

Parameters
[in]cnt= Mailbox counter value [0..7]
Returns
next mailbox counter value

Definition at line 907 of file ethercatmain.c.

◆ ec_packeterror()

void ec_packeterror ( uint16  Slave,
uint16  Index,
uint8  SubIdx,
uint16  ErrorCode 
)

Definition at line 2019 of file ethercatmain.c.

◆ ec_poperror()

boolean ec_poperror ( ec_errort Ec)

Definition at line 2009 of file ethercatmain.c.

◆ ec_pusherror()

void ec_pusherror ( const ec_errort Ec)

Definition at line 2004 of file ethercatmain.c.

◆ ec_readeeprom()

uint32 ec_readeeprom ( uint16  slave,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache.

Parameters
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 32bit
See also
ecx_readeeprom

Definition at line 2220 of file ethercatmain.c.

◆ ec_readeeprom1()

void ec_readeeprom1 ( uint16  slave,
uint16  eeproma 
)

Read EEPROM from slave bypassing cache. Parallel read step 1, make request to slave.

Parameters
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM
See also
ecx_readeeprom1

Definition at line 2318 of file ethercatmain.c.

◆ ec_readeeprom2()

uint32 ec_readeeprom2 ( uint16  slave,
int  timeout 
)

Read EEPROM from slave bypassing cache. Parallel read step 2, actual read from slave.

Parameters
[in]slave= Slave number
[in]timeout= Timeout in us.
Returns
EEPROM data 32bit
See also
ecx_readeeprom2

Definition at line 2330 of file ethercatmain.c.

◆ ec_readeepromAP()

uint64 ec_readeepromAP ( uint16  aiadr,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache. APRD method.

Parameters
[in]aiadr= auto increment address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 64bit or 32bit

Definition at line 2264 of file ethercatmain.c.

◆ ec_readeepromFP()

uint64 ec_readeepromFP ( uint16  configadr,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache. FPRD method.

Parameters
[in]configadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 64bit or 32bit
See also
ecx_readeepromFP

Definition at line 2294 of file ethercatmain.c.

◆ ec_readstate()

int ec_readstate ( void  )

Read all slave states in ec_slave.

Returns
lowest state found
See also
ecx_readstate

Definition at line 2138 of file ethercatmain.c.

◆ ec_receive_processdata()

int ec_receive_processdata ( int  timeout)

Definition at line 2393 of file ethercatmain.c.

◆ ec_receive_processdata_group()

int ec_receive_processdata_group ( uint8  group,
int  timeout 
)

Receive processdata from slaves. Second part from ec_send_processdata(). Received datagrams are recombined with the processdata with help from the stack. If a datagram contains input processdata it copies it to the processdata structure.

Parameters
[in]group= group number
[in]timeout= Timeout in us.
Returns
Work counter.
See also
ecx_receive_processdata_group

Definition at line 2378 of file ethercatmain.c.

◆ ec_send_overlap_processdata()

int ec_send_overlap_processdata ( void  )

Definition at line 2388 of file ethercatmain.c.

◆ ec_send_overlap_processdata_group()

int ec_send_overlap_processdata_group ( uint8  group)

Transmit processdata to slaves. Uses LRW, or LRD/LWR if LRW is not allowed (blockLRW). Both the input and output processdata are transmitted in the overlapped IOmap. The outputs with the actual data, the inputs replace the output data in the returning frame. The inputs are gathered with the receive processdata function. In contrast to the base LRW function this function is non-blocking. If the processdata does not fit in one datagram, multiple are used. In order to recombine the slave response, a stack is used.

Parameters
[in]group= group number
Returns
>0 if processdata is transmitted.
See also
ecx_send_overlap_processdata_group

Definition at line 2364 of file ethercatmain.c.

◆ ec_send_processdata()

int ec_send_processdata ( void  )

Definition at line 2383 of file ethercatmain.c.

◆ ec_send_processdata_group()

int ec_send_processdata_group ( uint8  group)

Transmit processdata to slaves. Uses LRW, or LRD/LWR if LRW is not allowed (blockLRW). Both the input and output processdata are transmitted. The outputs with the actual data, the inputs have a placeholder. The inputs are gathered with the receive processdata function. In contrast to the base LRW function this function is non-blocking. If the processdata does not fit in one datagram, multiple are used. In order to recombine the slave response, a stack is used.

Parameters
[in]group= group number
Returns
>0 if processdata is transmitted.
See also
ecx_send_processdata_group

Definition at line 2347 of file ethercatmain.c.

◆ ec_siifind()

int16 ec_siifind ( uint16  slave,
uint16  cat 
)

Find SII section header in slave EEPROM.

Parameters
[in]slave= slave number
[in]cat= section category
Returns
byte address of section at section length entry, if not available then 0
See also
ecx_siifind

Definition at line 2072 of file ethercatmain.c.

◆ ec_siiFMMU()

uint16 ec_siiFMMU ( uint16  slave,
ec_eepromFMMUt FMMU 
)

Get FMMU data from SII FMMU section in slave EEPROM.

Parameters
[in]slave= slave number
[out]FMMU= FMMU struct from SII, max. 4 FMMU's
Returns
number of FMMU's defined in section
See also
ecx_siiFMMU

Definition at line 2094 of file ethercatmain.c.

◆ ec_siigetbyte()

uint8 ec_siigetbyte ( uint16  slave,
uint16  address 
)

Read one byte from slave EEPROM via cache. If the cache location is empty then a read request is made to the slave. Depending on the slave capabillities the request is 4 or 8 bytes.

Parameters
[in]slave= slave number
[in]address= eeprom address in bytes (slave uses words)
Returns
requested byte, if not available then 0xff
See also
ecx_siigetbyte

Definition at line 2061 of file ethercatmain.c.

◆ ec_siiPDO()

int ec_siiPDO ( uint16  slave,
ec_eepromPDOt PDO,
uint8  t 
)

Get PDO data from SII PDO section in slave EEPROM.

Parameters
[in]slave= slave number
[out]PDO= PDO struct from SII
[in]t= 0=RXPDO 1=TXPDO
Returns
mapping size in bits of PDO
See also
ecx_siiPDO

Definition at line 2129 of file ethercatmain.c.

◆ ec_siiSM()

uint16 ec_siiSM ( uint16  slave,
ec_eepromSMt SM 
)

Get SM data from SII SM section in slave EEPROM.

Parameters
[in]slave= slave number
[out]SM= first SM struct from SII
Returns
number of SM's defined in section
See also
ecx_siiSM

Definition at line 2105 of file ethercatmain.c.

◆ ec_siiSMnext()

uint16 ec_siiSMnext ( uint16  slave,
ec_eepromSMt SM,
uint16  n 
)

Get next SM data from SII SM section in slave EEPROM.

Parameters
[in]slave= slave number
[out]SM= first SM struct from SII
[in]n= SM number
Returns
>0 if OK
See also
ecx_siiSMnext

Definition at line 2117 of file ethercatmain.c.

◆ ec_siistring()

void ec_siistring ( char *  str,
uint16  slave,
uint16  Sn 
)

Get string from SII string section in slave EEPROM.

Parameters
[out]str= requested string, 0x00 if not found
[in]slave= slave number
[in]Sn= string number
See also
ecx_siistring

Definition at line 2083 of file ethercatmain.c.

◆ ec_statecheck()

uint16 ec_statecheck ( uint16  slave,
uint16  reqstate,
int  timeout 
)

Check actual slave state. This is a blocking function.

Parameters
[in]slave= Slave number, 0 = all slaves
[in]reqstate= Requested state
[in]timeout= Timeout value in us
Returns
Requested state, or found state after timeout.
See also
ecx_statecheck

Definition at line 2162 of file ethercatmain.c.

◆ ec_writeeeprom()

int ec_writeeeprom ( uint16  slave,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache.

Parameters
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK
See also
ecx_writeeeprom

Definition at line 2233 of file ethercatmain.c.

◆ ec_writeeepromAP()

int ec_writeeepromAP ( uint16  aiadr,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache. APWR method.

Parameters
[in]aiadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK
See also
ecx_writeeepromAP

Definition at line 2277 of file ethercatmain.c.

◆ ec_writeeepromFP()

int ec_writeeepromFP ( uint16  configadr,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache. FPWR method.

Parameters
[in]configadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK
See also
ecx_writeeepromFP

Definition at line 2307 of file ethercatmain.c.

◆ ec_writestate()

int ec_writestate ( uint16  slave)

Write slave state, if slave = 0 then write to all slaves. The function does not check if the actual state is changed.

Parameters
[in]slave= Slave number, 0 = master
Returns
0
See also
ecx_writestate

Definition at line 2149 of file ethercatmain.c.

◆ ecx_clearindex()

static void ecx_clearindex ( ecx_contextt context)
static

Clear the idx stack.

Parameters
context= context struct

Definition at line 1677 of file ethercatmain.c.

◆ ecx_close()

void ecx_close ( ecx_contextt context)

Close lib.

Parameters
[in]context= context struct

Definition at line 321 of file ethercatmain.c.

◆ ecx_eeprom2master()

int ecx_eeprom2master ( ecx_contextt context,
uint16  slave 
)

Set eeprom control to master. Only if set to PDI.

Parameters
[in]context= context struct
[in]slave= Slave number
Returns
>0 if OK

Definition at line 1189 of file ethercatmain.c.

◆ ecx_eeprom2pdi()

int ecx_eeprom2pdi ( ecx_contextt context,
uint16  slave 
)

Set eeprom control to PDI. Only if set to master.

Parameters
[in]context= context struct
[in]slave= Slave number
Returns
>0 if OK

Definition at line 1222 of file ethercatmain.c.

◆ ecx_eeprom_waitnotbusyAP()

uint16 ecx_eeprom_waitnotbusyAP ( ecx_contextt context,
uint16  aiadr,
uint16 estat,
int  timeout 
)

Definition at line 1243 of file ethercatmain.c.

◆ ecx_eeprom_waitnotbusyFP()

uint16 ecx_eeprom_waitnotbusyFP ( ecx_contextt context,
uint16  configadr,
uint16 estat,
int  timeout 
)

Definition at line 1412 of file ethercatmain.c.

◆ ecx_esidump()

void ecx_esidump ( ecx_contextt context,
uint16  slave,
uint8 esibuf 
)

Dump complete EEPROM data from slave in buffer.

Parameters
[in]context= context struct
[in]slave= Slave number
[out]esibuf= EEPROM data buffer, make sure it is big enough.

Definition at line 1114 of file ethercatmain.c.

◆ ecx_FPRD_multi()

int ecx_FPRD_multi ( ecx_contextt context,
int  n,
uint16 configlst,
ec_alstatust slstatlst,
int  timeout 
)

Definition at line 683 of file ethercatmain.c.

◆ ecx_init()

int ecx_init ( ecx_contextt context,
const char *  ifname 
)

Initialise lib in single NIC mode

Parameters
[in]context= context struct
[in]ifname= Dev name, f.e. "eth0"
Returns
>0 if OK

Definition at line 288 of file ethercatmain.c.

◆ ecx_init_redundant()

int ecx_init_redundant ( ecx_contextt context,
ecx_redportt redport,
const char *  ifname,
char *  if2name 
)

Initialise lib in redundant NIC mode

Parameters
[in]context= context struct
[in]redport= pointer to redport, redundant port data
[in]ifname= Primary Dev name, f.e. "eth0"
[in]if2name= Secondary Dev name, f.e. "eth1"
Returns
>0 if OK

Definition at line 300 of file ethercatmain.c.

◆ ecx_iserror()

boolean ecx_iserror ( ecx_contextt context)

Check if error list has entries.

Parameters
[in]context= context struct
Returns
TRUE if error list contains entries.

Definition at line 206 of file ethercatmain.c.

◆ ecx_main_send_processdata()

static int ecx_main_send_processdata ( ecx_contextt context,
uint8  group,
boolean  use_overlap_io 
)
static

Transmit processdata to slaves. Uses LRW, or LRD/LWR if LRW is not allowed (blockLRW). Both the input and output processdata are transmitted. The outputs with the actual data, the inputs have a placeholder. The inputs are gathered with the receive processdata function. In contrast to the base LRW function this function is non-blocking. If the processdata does not fit in one datagram, multiple are used. In order to recombine the slave response, a stack is used.

Parameters
[in]context= context struct
[in]group= group number
[in]use_overlap_io= flag if overlapped iomap is used
Returns
>0 if processdata is transmitted.

Definition at line 1697 of file ethercatmain.c.

◆ ecx_mbxemergencyerror()

static void ecx_mbxemergencyerror ( ecx_contextt context,
uint16  Slave,
uint16  ErrorCode,
uint16  ErrorReg,
uint8  b1,
uint16  w1,
uint16  w2 
)
static

Report Mailbox Emergency Error

Parameters
[in]context= context struct
[in]Slave= Slave number
[in]ErrorCode= Following EtherCAT specification
[in]ErrorReg
[in]b1
[in]w1
[in]w2

Definition at line 264 of file ethercatmain.c.

◆ ecx_mbxempty()

int ecx_mbxempty ( ecx_contextt context,
uint16  slave,
int  timeout 
)

Check if IN mailbox of slave is empty.

Parameters
[in]context= context struct
[in]slave= Slave number
[in]timeout= Timeout in us
Returns
>0 is success

Definition at line 932 of file ethercatmain.c.

◆ ecx_mbxerror()

static void ecx_mbxerror ( ecx_contextt context,
uint16  Slave,
uint16  Detail 
)
static

Report Mailbox Error

Parameters
[in]context= context struct
[in]Slave= Slave number
[in]Detail= Following EtherCAT specification

Definition at line 240 of file ethercatmain.c.

◆ ecx_mbxreceive()

int ecx_mbxreceive ( ecx_contextt context,
uint16  slave,
ec_mbxbuft mbx,
int  timeout 
)

Read OUT mailbox from slave. Supports Mailbox Link Layer with repeat requests.

Parameters
[in]context= context struct
[in]slave= Slave number
[out]mbx= Mailbox data
[in]timeout= Timeout in us
Returns
Work counter (>0 is success)

Definition at line 1001 of file ethercatmain.c.

◆ ecx_mbxsend()

int ecx_mbxsend ( ecx_contextt context,
uint16  slave,
ec_mbxbuft mbx,
int  timeout 
)

Write IN mailbox to slave.

Parameters
[in]context= context struct
[in]slave= Slave number
[out]mbx= Mailbox data
[in]timeout= Timeout in us
Returns
Work counter (>0 is success)

Definition at line 968 of file ethercatmain.c.

◆ ecx_packeterror()

void ecx_packeterror ( ecx_contextt context,
uint16  Slave,
uint16  Index,
uint8  SubIdx,
uint16  ErrorCode 
)

Report packet error

Parameters
[in]context= context struct
[in]Slave= Slave number
[in]Index= Index that generated error
[in]SubIdx= Subindex that generated error
[in]ErrorCode= Error code

Definition at line 219 of file ethercatmain.c.

◆ ecx_poperror()

boolean ecx_poperror ( ecx_contextt context,
ec_errort Ec 
)

Pops an error from the list.

Parameters
[in]context= context struct
[out]Ec= Struct describing the error.
Returns
TRUE if an error was popped.

Definition at line 180 of file ethercatmain.c.

◆ ecx_pullindex()

static int ecx_pullindex ( ecx_contextt context)
static

Pull index of segmented LRD/LWR/LRW combination.

Parameters
[in]context= context struct
Returns
Stack location, -1 if stack is empty.

Definition at line 1660 of file ethercatmain.c.

◆ ecx_pusherror()

void ecx_pusherror ( ecx_contextt context,
const ec_errort Ec 
)

Pushes an error on the error list.

Parameters
[in]context= context struct
[in]Ecpointer describing the error.

Definition at line 154 of file ethercatmain.c.

◆ ecx_pushindex()

static void ecx_pushindex ( ecx_contextt context,
uint8  idx,
void *  data,
uint16  length 
)
static

Push index of segmented LRD/LWR/LRW combination.

Parameters
[in]context= context struct
[in]idx= Used datagram index.
[in]data= Pointer to process data segment.
[in]length= Length of data segment in bytes.

Definition at line 1645 of file ethercatmain.c.

◆ ecx_readeeprom()

uint32 ecx_readeeprom ( ecx_contextt context,
uint16  slave,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache.

Parameters
[in]context= context struct
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 32bit

Definition at line 1157 of file ethercatmain.c.

◆ ecx_readeeprom1()

void ecx_readeeprom1 ( ecx_contextt context,
uint16  slave,
uint16  eeproma 
)

Read EEPROM from slave bypassing cache. Parallel read step 1, make request to slave.

Parameters
[in]context= context struct
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM

Definition at line 1585 of file ethercatmain.c.

◆ ecx_readeeprom2()

uint32 ecx_readeeprom2 ( ecx_contextt context,
uint16  slave,
int  timeout 
)

Read EEPROM from slave bypassing cache. Parallel read step 2, actual read from slave.

Parameters
[in]context= context struct
[in]slave= Slave number
[in]timeout= Timeout in us.
Returns
EEPROM data 32bit

Definition at line 1618 of file ethercatmain.c.

◆ ecx_readeepromAP()

uint64 ecx_readeepromAP ( ecx_contextt context,
uint16  aiadr,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache. APRD method.

Parameters
[in]context= context struct
[in]aiadr= auto increment address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 64bit or 32bit

Definition at line 1275 of file ethercatmain.c.

◆ ecx_readeepromFP()

uint64 ecx_readeepromFP ( ecx_contextt context,
uint16  configadr,
uint16  eeproma,
int  timeout 
)

Read EEPROM from slave bypassing cache. FPRD method.

Parameters
[in]context= context struct
[in]configadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]timeout= Timeout in us.
Returns
EEPROM data 64bit or 32bit

Definition at line 1444 of file ethercatmain.c.

◆ ecx_readstate()

int ecx_readstate ( ecx_contextt context)

Read all slave states in ec_slave.

Parameters
[in]context= context struct
Returns
lowest state found

Definition at line 723 of file ethercatmain.c.

◆ ecx_receive_processdata()

int ecx_receive_processdata ( ecx_contextt context,
int  timeout 
)

Definition at line 1998 of file ethercatmain.c.

◆ ecx_receive_processdata_group()

int ecx_receive_processdata_group ( ecx_contextt context,
uint8  group,
int  timeout 
)

Receive processdata from slaves. Second part from ec_send_processdata(). Received datagrams are recombined with the processdata with help from the stack. If a datagram contains input processdata it copies it to the processdata structure.

Parameters
[in]context= context struct
[in]group= group number
[in]timeout= Timeout in us.
Returns
Work counter.

Definition at line 1910 of file ethercatmain.c.

◆ ecx_send_overlap_processdata()

int ecx_send_overlap_processdata ( ecx_contextt context)

Definition at line 1993 of file ethercatmain.c.

◆ ecx_send_overlap_processdata_group()

int ecx_send_overlap_processdata_group ( ecx_contextt context,
uint8  group 
)

Transmit processdata to slaves. Uses LRW, or LRD/LWR if LRW is not allowed (blockLRW). Both the input and output processdata are transmitted in the overlapped IOmap. The outputs with the actual data, the inputs replace the output data in the returning frame. The inputs are gathered with the receive processdata function. In contrast to the base LRW function this function is non-blocking. If the processdata does not fit in one datagram, multiple are used. In order to recombine the slave response, a stack is used.

Parameters
[in]context= context struct
[in]group= group number
Returns
>0 if processdata is transmitted.

Definition at line 1879 of file ethercatmain.c.

◆ ecx_send_processdata()

int ecx_send_processdata ( ecx_contextt context)

Definition at line 1988 of file ethercatmain.c.

◆ ecx_send_processdata_group()

int ecx_send_processdata_group ( ecx_contextt context,
uint8  group 
)

Transmit processdata to slaves. Uses LRW, or LRD/LWR if LRW is not allowed (blockLRW). Both the input and output processdata are transmitted. The outputs with the actual data, the inputs have a placeholder. The inputs are gathered with the receive processdata function. In contrast to the base LRW function this function is non-blocking. If the processdata does not fit in one datagram, multiple are used. In order to recombine the slave response, a stack is used.

Parameters
[in]context= context struct
[in]group= group number
Returns
>0 if processdata is transmitted.

Definition at line 1896 of file ethercatmain.c.

◆ ecx_siifind()

int16 ecx_siifind ( ecx_contextt context,
uint16  slave,
uint16  cat 
)

Find SII section header in slave EEPROM.

Parameters
[in]context= context struct
[in]slave= slave number
[in]cat= section category
Returns
byte address of section at section length entry, if not available then 0

Definition at line 405 of file ethercatmain.c.

◆ ecx_siiFMMU()

uint16 ecx_siiFMMU ( ecx_contextt context,
uint16  slave,
ec_eepromFMMUt FMMU 
)

Get FMMU data from SII FMMU section in slave EEPROM.

Parameters
[in]context= context struct
[in]slave= slave number
[out]FMMU= FMMU struct from SII, max. 4 FMMU's
Returns
number of FMMU's defined in section

Definition at line 503 of file ethercatmain.c.

◆ ecx_siigetbyte()

uint8 ecx_siigetbyte ( ecx_contextt context,
uint16  slave,
uint16  address 
)

Read one byte from slave EEPROM via cache. If the cache location is empty then a read request is made to the slave. Depending on the slave capabilities the request is 4 or 8 bytes.

Parameters
[in]context= context struct
[in]slave= slave number
[in]address= eeprom address in bytes (slave uses words)
Returns
requested byte, if not available then 0xff

Definition at line 334 of file ethercatmain.c.

◆ ecx_siiPDO()

int ecx_siiPDO ( ecx_contextt context,
uint16  slave,
ec_eepromPDOt PDO,
uint8  t 
)

Get PDO data from SII PDO section in slave EEPROM.

Parameters
[in]context= context struct
[in]slave= slave number
[out]PDO= PDO struct from SII
[in]t= 0=RXPDO 1=TXPDO
Returns
mapping size in bits of PDO

Definition at line 614 of file ethercatmain.c.

◆ ecx_siiSM()

uint16 ecx_siiSM ( ecx_contextt context,
uint16  slave,
ec_eepromSMt SM 
)

Get SM data from SII SM section in slave EEPROM.

Parameters
[in]context= context struct
[in]slave= slave number
[out]SM= first SM struct from SII
Returns
number of SM's defined in section

Definition at line 543 of file ethercatmain.c.

◆ ecx_siiSMnext()

uint16 ecx_siiSMnext ( ecx_contextt context,
uint16  slave,
ec_eepromSMt SM,
uint16  n 
)

Get next SM data from SII SM section in slave EEPROM.

Parameters
[in]context= context struct
[in]slave= slave number
[out]SM= first SM struct from SII
[in]n= SM number
Returns
>0 if OK

Definition at line 580 of file ethercatmain.c.

◆ ecx_siistring()

void ecx_siistring ( ecx_contextt context,
char *  str,
uint16  slave,
uint16  Sn 
)

Get string from SII string section in slave EEPROM.

Parameters
[in]context= context struct
[out]str= requested string, 0x00 if not found
[in]slave= slave number
[in]Sn= string number

Definition at line 445 of file ethercatmain.c.

◆ ecx_statecheck()

uint16 ecx_statecheck ( ecx_contextt context,
uint16  slave,
uint16  reqstate,
int  timeout 
)

Check actual slave state. This is a blocking function. To refresh the state of all slaves ecx_readstate()should be called

Parameters
[in]context= context struct
[in]slave= Slave number, 0 = all slaves (only the "slavelist[0].state" is refreshed)
[in]reqstate= Requested state
[in]timeout= Timeout value in us
Returns
Requested state, or found state after timeout.

Definition at line 862 of file ethercatmain.c.

◆ ecx_writeeeprom()

int ecx_writeeeprom ( ecx_contextt context,
uint16  slave,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache.

Parameters
[in]context= context struct
[in]slave= Slave number
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK

Definition at line 1175 of file ethercatmain.c.

◆ ecx_writeeepromAP()

int ecx_writeeepromAP ( ecx_contextt context,
uint16  aiadr,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache. APWR method.

Parameters
[in]context= context struct
[in]aiadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK

Definition at line 1355 of file ethercatmain.c.

◆ ecx_writeeepromFP()

int ecx_writeeepromFP ( ecx_contextt context,
uint16  configadr,
uint16  eeproma,
uint16  data,
int  timeout 
)

Write EEPROM to slave bypassing cache. FPWR method.

Parameters
[in]context= context struct
[in]configadr= configured address of slave
[in]eeproma= (WORD) Address in the EEPROM
[in]data= 16bit data
[in]timeout= Timeout in us.
Returns
>0 if OK

Definition at line 1524 of file ethercatmain.c.

◆ ecx_writestate()

int ecx_writestate ( ecx_contextt context,
uint16  slave 
)

Write slave state, if slave = 0 then write to all slaves. The function does not check if the actual state is changed.

Parameters
[in]context= context struct
[in]slave= Slave number, 0 = master
Returns
Workcounter or EC_NOFRAME

Definition at line 832 of file ethercatmain.c.

Variable Documentation

◆ ec_DCtime

int64 ec_DCtime

Definition at line 95 of file ethercatmain.c.

◆ ec_elist

ec_eringt ec_elist
static

current slave for EEPROM cache buffer

Definition at line 78 of file ethercatmain.c.

◆ ec_esibuf

uint8 ec_esibuf[EC_MAXEEPBUF]
static

cache for EEPROM read functions

Definition at line 74 of file ethercatmain.c.

◆ ec_esimap

uint32 ec_esimap[EC_MAXEEPBITMAP]
static

bitmap for filled cache buffer bytes

Definition at line 76 of file ethercatmain.c.

◆ ec_FMMU

ec_eepromFMMUt ec_FMMU
static

buffer for EEPROM FMMU data

Definition at line 91 of file ethercatmain.c.

◆ ec_group

slave group structure

Definition at line 71 of file ethercatmain.c.

◆ ec_idxstack

Definition at line 79 of file ethercatmain.c.

◆ ec_PDOassign

PDO assign struct to store data of one slave

Definition at line 84 of file ethercatmain.c.

◆ ec_PDOdesc

PDO description struct to store data of one slave

Definition at line 86 of file ethercatmain.c.

◆ ec_slave

Main slave data array. Each slave found on the network gets its own record. ec_slave[0] is reserved for the master. Structure gets filled in by the configuration function ec_config().

Definition at line 67 of file ethercatmain.c.

◆ ec_slavecount

int ec_slavecount

number of slaves found on the network

Definition at line 69 of file ethercatmain.c.

◆ ec_SM

ec_eepromSMt ec_SM
static

buffer for EEPROM SM data

Definition at line 89 of file ethercatmain.c.

◆ ec_SMcommtype

SyncManager Communication Type struct to store data of one slave

Definition at line 82 of file ethercatmain.c.

◆ EcatError

boolean EcatError = FALSE

Global variable TRUE if error available in error stack

Definition at line 93 of file ethercatmain.c.

◆ ecx_context

Initial value:
= {
&ec_slave[0],
&ec_group[0],
&ec_esibuf[0],
&ec_esimap[0],
0,
0,
0,
&ec_PDOdesc[0],
&ec_SM,
NULL,
NULL,
0
}
static uint32 ec_esimap[EC_MAXEEPBITMAP]
Definition: ethercatmain.c:76
#define EC_MAXGROUP
Definition: ethercatmain.h:27
int64 ec_DCtime
Definition: ethercatmain.c:95
static ec_eepromFMMUt ec_FMMU
Definition: ethercatmain.c:91
ecx_portt ecx_port
Definition: ethercatmain.c:97
boolean EcatError
Definition: ethercatmain.c:93
static ec_eepromSMt ec_SM
Definition: ethercatmain.c:89
static ec_idxstackT ec_idxstack
Definition: ethercatmain.c:79
#define EC_MAXSLAVE
Definition: ethercatmain.h:25
int ec_slavecount
Definition: ethercatmain.c:69
static ec_eringt ec_elist
Definition: ethercatmain.c:78
static uint8 ec_esibuf[EC_MAXEEPBUF]
Definition: ethercatmain.c:74

Definition at line 100 of file ethercatmain.c.

◆ ecx_port

Definition at line 97 of file ethercatmain.c.

◆ ecx_redport

Definition at line 98 of file ethercatmain.c.



soem
Author(s): Arthur Ketels and M.J.G. van den Molengraft
autogenerated on Mon Feb 28 2022 23:46:57