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

Main EtherCAT functions. More...

#include <stdio.h>
#include <string.h>
#include <sys/time.h>
#include <arpa/inet.h>
#include <unistd.h>
#include <youbot_driver/soem/ethercattype.h>
#include <youbot_driver/soem/nicdrv.h>
#include <youbot_driver/soem/ethercatbase.h>
#include <youbot_driver/soem/ethercatmain.h>
Include dependency graph for ethercatmain.c:

Go to the source code of this file.

Classes

struct  ec_emcyt
struct  ec_eringt
struct  ec_idxstackT
struct  PACKED

Defines

#define EC_LOCALDELAY   200

Typedefs

typedef struct PACKED ec_eepromt

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, uint8 test)
int ec_init (const char *ifname)
int ec_init_redundant (const char *ifname, const char *if2name)
boolean ec_iserror (void)
static void ec_mbxemergencyerror (uint16 Slave, uint16 ErrorCode, uint16 ErrorReg, uint8 b1, uint16 w1, uint16 w2)
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)
static int ec_pullindex (void)
void ec_pusherror (const ec_errort *Ec)
static void ec_pushindex (uint8 idx, void *data, uint16 length)
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_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)

Variables

static uint16 ec_DCl
int64 ec_DCtime
uint16 ec_DCtO
static ec_eringt ec_elist
ec_groupt ec_group [EC_MAXGROUP]
static ec_idxstackT ec_idxstack
ec_slavet ec_slave [EC_MAXSLAVE]
int ec_slavecount
boolean EcatError = FALSE
static uint8 esibuf [EC_MAXEEPBUF]
static uint32 esimap [EC_MAXEEPBITMAP]
static uint16 esislave = 0

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.


Define Documentation

#define EC_LOCALDELAY   200

delay in us for eeprom ready loop

Definition at line 64 of file ethercatmain.c.


Typedef Documentation

typedef struct PACKED ec_eepromt

record for ethercat eeprom communications


Function Documentation

void ec_clearmbx ( ec_mbxbuft Mbx)

Clear mailbox buffer.

Parameters:
[out]Mbx= Mailbox buffer to clear

Definition at line 694 of file ethercatmain.c.

void ec_close ( void  )

Close lib.

Definition at line 260 of file ethercatmain.c.

int ec_eeprom2master ( uint16  slave)

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

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

Definition at line 915 of file ethercatmain.c.

int ec_eeprom2pdi ( uint16  slave)

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

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

Definition at line 945 of file ethercatmain.c.

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

Definition at line 965 of file ethercatmain.c.

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

Definition at line 1125 of file ethercatmain.c.

void ec_esidump ( uint16  slave,
uint8 esibuf,
uint8  test 
)

Dump complete EEPROM data from slave in buffer.

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

Definition at line 850 of file ethercatmain.c.

int ec_init ( const char *  ifname)

Initialise lib in single NIC mode

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

Definition at line 231 of file ethercatmain.c.

int ec_init_redundant ( const char *  ifname,
const 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

Definition at line 241 of file ethercatmain.c.

boolean ec_iserror ( void  )

Check if error list has entries.

Returns:
TRUE if error list contains entries.

Definition at line 175 of file ethercatmain.c.

static void ec_mbxemergencyerror ( uint16  Slave,
uint16  ErrorCode,
uint16  ErrorReg,
uint8  b1,
uint16  w1,
uint16  w2 
) [static]

Report Mailbox Emergency Error

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

Definition at line 210 of file ethercatmain.c.

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

Definition at line 704 of file ethercatmain.c.

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)

Definition at line 765 of file ethercatmain.c.

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)

Definition at line 735 of file ethercatmain.c.

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 683 of file ethercatmain.c.

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

Report packet error

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

Definition at line 187 of file ethercatmain.c.

Pops an error from the list.

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

Definition at line 154 of file ethercatmain.c.

static int ec_pullindex ( void  ) [static]

Pull index of segmented LRD/LWR/LRW combination.

Returns:
Stack location, -1 if stack is empty.

Definition at line 1361 of file ethercatmain.c.

void ec_pusherror ( const ec_errort Ec)

Pushes an error on the error list.

Parameters:
[in]EcStruct describing the error.

Definition at line 135 of file ethercatmain.c.

static void ec_pushindex ( uint8  idx,
void *  data,
uint16  length 
) [static]

Push index of segmented LRD/LWR/LRW combination.

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

Definition at line 1347 of file ethercatmain.c.

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

Definition at line 886 of file ethercatmain.c.

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

Definition at line 1288 of file ethercatmain.c.

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

Definition at line 1318 of file ethercatmain.c.

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 993 of file ethercatmain.c.

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

Definition at line 1153 of file ethercatmain.c.

int ec_readstate ( void  )

Read all slave states in ec_slave.

Returns:
lowest state found

Definition at line 585 of file ethercatmain.c.

int ec_receive_processdata ( int  timeout)

Definition at line 1560 of file ethercatmain.c.

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]timeout= Timeout in us.
Returns:
Work counter.

Definition at line 1512 of file ethercatmain.c.

int ec_send_processdata ( void  )

Definition at line 1555 of file ethercatmain.c.

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.

Returns:
>0 if processdata is transmitted.

Definition at line 1383 of file ethercatmain.c.

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

Definition at line 341 of file ethercatmain.c.

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

Definition at line 419 of file ethercatmain.c.

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

Definition at line 273 of file ethercatmain.c.

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

Definition at line 519 of file ethercatmain.c.

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

Definition at line 455 of file ethercatmain.c.

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

Definition at line 489 of file ethercatmain.c.

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

Definition at line 377 of file ethercatmain.c.

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= Timout value in us
Returns:
Requested state, or found state after timeout.

Definition at line 639 of file ethercatmain.c.

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

Definition at line 902 of file ethercatmain.c.

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

Definition at line 1069 of file ethercatmain.c.

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

Definition at line 1229 of file ethercatmain.c.

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

Definition at line 615 of file ethercatmain.c.


Variable Documentation

uint16 ec_DCl [static]

Definition at line 128 of file ethercatmain.c.

Definition at line 129 of file ethercatmain.c.

Definition at line 127 of file ethercatmain.c.

ec_eringt ec_elist [static]

Definition at line 121 of file ethercatmain.c.

slave group structure

Definition at line 113 of file ethercatmain.c.

Definition at line 122 of file ethercatmain.c.

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 109 of file ethercatmain.c.

number of slaves found on the network

Definition at line 111 of file ethercatmain.c.

Global variable TRUE if error available in error stack

Definition at line 125 of file ethercatmain.c.

cache for EEPROM read functions

Definition at line 116 of file ethercatmain.c.

bitmap for filled cache buffer bytes

Definition at line 118 of file ethercatmain.c.

uint16 esislave = 0 [static]

current slave for EEPROM cache buffer

Definition at line 120 of file ethercatmain.c.



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