|
SOEM
v1.3.0
|
Main EtherCAT functions. More...
#include <stdio.h>#include <string.h>#include "osal.h"#include "oshw.h"#include "ethercattype.h"#include "ethercatbase.h"#include "ethercatmain.h"Data Structures | |
| struct | ec_eepromt |
| struct | ec_mbxerrort |
| struct | ec_emcyt |
Macros | |
| #define | EC_LOCALDELAY 200 |
Functions | |
| ec_adaptert * | ec_find_adapters (void) |
| void | ec_free_adapters (ec_adaptert *adapter) |
| void | ecx_pusherror (ecx_contextt *context, const ec_errort *Ec) |
| boolean | ecx_poperror (ecx_contextt *context, ec_errort *Ec) |
| boolean | ecx_iserror (ecx_contextt *context) |
| void | ecx_packeterror (ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode) |
| static void | ecx_mbxerror (ecx_contextt *context, uint16 Slave, uint16 Detail) |
| static void | ecx_mbxemergencyerror (ecx_contextt *context, uint16 Slave, uint16 ErrorCode, uint16 ErrorReg, uint8 b1, uint16 w1, uint16 w2) |
| int | ecx_init (ecx_contextt *context, char *ifname) |
| int | ecx_init_redundant (ecx_contextt *context, ecx_redportt *redport, char *ifname, char *if2name) |
| void | ecx_close (ecx_contextt *context) |
| uint8 | ecx_siigetbyte (ecx_contextt *context, uint16 slave, uint16 address) |
| int16 | ecx_siifind (ecx_contextt *context, uint16 slave, uint16 cat) |
| void | ecx_siistring (ecx_contextt *context, char *str, uint16 slave, uint16 Sn) |
| uint16 | ecx_siiFMMU (ecx_contextt *context, uint16 slave, ec_eepromFMMUt *FMMU) |
| uint16 | ecx_siiSM (ecx_contextt *context, uint16 slave, ec_eepromSMt *SM) |
| uint16 | ecx_siiSMnext (ecx_contextt *context, uint16 slave, ec_eepromSMt *SM, uint16 n) |
| int | ecx_siiPDO (ecx_contextt *context, uint16 slave, ec_eepromPDOt *PDO, uint8 t) |
| int | ecx_readstate (ecx_contextt *context) |
| int | ecx_writestate (ecx_contextt *context, uint16 slave) |
| uint16 | ecx_statecheck (ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout) |
| uint8 | ec_nextmbxcnt (uint8 cnt) |
| void | ec_clearmbx (ec_mbxbuft *Mbx) |
| int | ecx_mbxempty (ecx_contextt *context, uint16 slave, int timeout) |
| int | ecx_mbxsend (ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout) |
| int | ecx_mbxreceive (ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int timeout) |
| void | ecx_esidump (ecx_contextt *context, uint16 slave, uint8 *esibuf) |
| uint32 | ecx_readeeprom (ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout) |
| int | ecx_writeeeprom (ecx_contextt *context, uint16 slave, uint16 eeproma, uint16 data, int timeout) |
| 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) |
| uint64 | ecx_readeepromAP (ecx_contextt *context, uint16 aiadr, uint16 eeproma, int timeout) |
| int | ecx_writeeepromAP (ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint16 data, int timeout) |
| uint16 | ecx_eeprom_waitnotbusyFP (ecx_contextt *context, uint16 configadr, uint16 *estat, int timeout) |
| uint64 | ecx_readeepromFP (ecx_contextt *context, uint16 configadr, uint16 eeproma, int timeout) |
| int | ecx_writeeepromFP (ecx_contextt *context, uint16 configadr, uint16 eeproma, uint16 data, int timeout) |
| void | ecx_readeeprom1 (ecx_contextt *context, uint16 slave, uint16 eeproma) |
| uint32 | ecx_readeeprom2 (ecx_contextt *context, uint16 slave, int timeout) |
| static void | ecx_pushindex (ecx_contextt *context, uint8 idx, void *data, uint16 length) |
| static int | ecx_pullindex (ecx_contextt *context) |
| int | ecx_send_processdata_group (ecx_contextt *context, uint8 group) |
| int | ecx_receive_processdata_group (ecx_contextt *context, uint8 group, int timeout) |
| int | ecx_send_processdata (ecx_contextt *context) |
| int | ecx_receive_processdata (ecx_contextt *context, int timeout) |
| void | ec_pusherror (const ec_errort *Ec) |
| boolean | ec_poperror (ec_errort *Ec) |
| boolean | ec_iserror (void) |
| void | ec_packeterror (uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode) |
| static void | ec_mbxerror (uint16 Slave, uint16 Detail) |
| static void | ec_mbxemergencyerror (uint16 Slave, uint16 ErrorCode, uint16 ErrorReg, uint8 b1, uint16 w1, uint16 w2) |
| int | ec_init (char *ifname) |
| int | ec_init_redundant (char *ifname, char *if2name) |
| void | ec_close (void) |
| uint8 | ec_siigetbyte (uint16 slave, uint16 address) |
| int16 | ec_siifind (uint16 slave, uint16 cat) |
| void | ec_siistring (char *str, uint16 slave, uint16 Sn) |
| uint16 | ec_siiFMMU (uint16 slave, ec_eepromFMMUt *FMMU) |
| uint16 | ec_siiSM (uint16 slave, ec_eepromSMt *SM) |
| uint16 | ec_siiSMnext (uint16 slave, ec_eepromSMt *SM, uint16 n) |
| int | ec_siiPDO (uint16 slave, ec_eepromPDOt *PDO, uint8 t) |
| int | ec_readstate (void) |
| int | ec_writestate (uint16 slave) |
| uint16 | ec_statecheck (uint16 slave, uint16 reqstate, int timeout) |
| int | ec_mbxempty (uint16 slave, int timeout) |
| int | ec_mbxsend (uint16 slave, ec_mbxbuft *mbx, int timeout) |
| int | ec_mbxreceive (uint16 slave, ec_mbxbuft *mbx, int timeout) |
| void | ec_esidump (uint16 slave, uint8 *esibuf) |
| uint32 | ec_readeeprom (uint16 slave, uint16 eeproma, int timeout) |
| int | ec_writeeeprom (uint16 slave, uint16 eeproma, uint16 data, int timeout) |
| int | ec_eeprom2master (uint16 slave) |
| int | ec_eeprom2pdi (uint16 slave) |
| uint16 | ec_eeprom_waitnotbusyAP (uint16 aiadr, uint16 *estat, int timeout) |
| uint64 | ec_readeepromAP (uint16 aiadr, uint16 eeproma, int timeout) |
| int | ec_writeeepromAP (uint16 aiadr, uint16 eeproma, uint16 data, int timeout) |
| uint16 | ec_eeprom_waitnotbusyFP (uint16 configadr, uint16 *estat, int timeout) |
| uint64 | ec_readeepromFP (uint16 configadr, uint16 eeproma, int timeout) |
| int | ec_writeeepromFP (uint16 configadr, uint16 eeproma, uint16 data, int timeout) |
| void | ec_readeeprom1 (uint16 slave, uint16 eeproma) |
| uint32 | ec_readeeprom2 (uint16 slave, int timeout) |
| int | ec_send_processdata_group (uint8 group) |
| int | ec_receive_processdata_group (uint8 group, int timeout) |
| int | ec_send_processdata (void) |
| int | ec_receive_processdata (int timeout) |
Variables | |
| PACKED_END ec_slavet | ec_slave [EC_MAXSLAVE] |
| int | ec_slavecount |
| ec_groupt | ec_group [EC_MAXGROUP] |
| static uint8 | esibuf [EC_MAXEEPBUF] |
| static uint32 | esimap [EC_MAXEEPBITMAP] |
| static ec_eringt | ec_elist |
| static ec_idxstackT | ec_idxstack |
| static ec_SMcommtypet | ec_SMcommtype |
| static ec_PDOassignt | ec_PDOassign |
| static ec_PDOdesct | ec_PDOdesc |
| static ec_eepromSMt | ec_SM |
| static ec_eepromFMMUt | ec_FMMU |
| boolean | EcatError = FALSE |
| int64 | ec_DCtime |
| ecx_portt | ecx_port |
| ecx_redportt | ecx_redport |
| ecx_contextt | ecx_context |
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.
| #define EC_LOCALDELAY 200 |
delay in us for eeprom ready loop
| void ec_clearmbx | ( | ec_mbxbuft * | Mbx | ) |
Clear mailbox buffer.
| [out] | Mbx | = Mailbox buffer to clear |
| 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_adaptert* ec_find_adapters | ( | void | ) |
Create list over available network adapters.
| void ec_free_adapters | ( | ec_adaptert * | adapter | ) |
Free dynamically allocated list over available network adapters.
| [in] | adapter | = Struct holding adapter name, description and pointer to next. |
| int ec_init | ( | char * | ifname | ) |
| int ec_init_redundant | ( | char * | ifname, |
| char * | if2name | ||
| ) |
| boolean ec_iserror | ( | void | ) |
|
static |
| int ec_mbxempty | ( | uint16 | slave, |
| int | timeout | ||
| ) |
|
static |
| 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 | ) |
Get index of next mailbox counter value. Used for Mailbox Link Layer.
| [in] | cnt | = Mailbox counter value [0..7] |
| 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_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 | ) |
| void ecx_close | ( | ecx_contextt * | context | ) |
Close lib.
| [in] | context | = context struct |
| int ecx_eeprom2master | ( | ecx_contextt * | context, |
| uint16 | slave | ||
| ) |
Set eeprom control to master. Only if set to PDI.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| int ecx_eeprom2pdi | ( | ecx_contextt * | context, |
| uint16 | slave | ||
| ) |
Set eeprom control to PDI. Only if set to master.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| 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 | ||
| ) |
Dump complete EEPROM data from slave in buffer.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [out] | esibuf | = EEPROM data buffer, make sure it is big enough. |
| int ecx_init | ( | ecx_contextt * | context, |
| char * | ifname | ||
| ) |
Initialise lib in single NIC mode
| [in] | context | = context struct |
| [in] | ifname | = Dev name, f.e. "eth0" |
| int ecx_init_redundant | ( | ecx_contextt * | context, |
| ecx_redportt * | redport, | ||
| char * | ifname, | ||
| char * | if2name | ||
| ) |
Initialise lib in redundant NIC mode
| [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" |
| boolean ecx_iserror | ( | ecx_contextt * | context | ) |
Check if error list has entries.
| [in] | context | = context struct |
|
static |
Report Mailbox Emergency Error
| [in] | context | = context struct |
| [in] | Slave | = Slave number |
| [in] | ErrorCode | = Following EtherCAT specification |
| [in] | ErrorReg | |
| [in] | b1 | |
| [in] | w1 | |
| [in] | w2 |
| int ecx_mbxempty | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| int | timeout | ||
| ) |
Check if IN mailbox of slave is empty.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [in] | timeout | = Timeout in us |
|
static |
Report Mailbox Error
| [in] | context | = context struct |
| [in] | Slave | = Slave number |
| [in] | Detail | = Following EtherCAT specification |
| 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.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [out] | mbx | = Mailbox data |
| [in] | timeout | = Timeout in us |
| int ecx_mbxsend | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| ec_mbxbuft * | mbx, | ||
| int | timeout | ||
| ) |
Write IN mailbox to slave.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [out] | mbx | = Mailbox data |
| [in] | timeout | = Timeout in us |
| void ecx_packeterror | ( | ecx_contextt * | context, |
| uint16 | Slave, | ||
| uint16 | Index, | ||
| uint8 | SubIdx, | ||
| uint16 | ErrorCode | ||
| ) |
Report packet error
| [in] | context | = context struct |
| [in] | Slave | = Slave number |
| [in] | Index | = Index that generated error |
| [in] | SubIdx | = Subindex that generated error |
| [in] | ErrorCode | = Error code |
| boolean ecx_poperror | ( | ecx_contextt * | context, |
| ec_errort * | Ec | ||
| ) |
Pops an error from the list.
| [in] | context | = context struct |
| [out] | Ec | = Struct describing the error. |
|
static |
Pull index of segmented LRD/LWR/LRW combination.
| [in] | context | = context struct |
| void ecx_pusherror | ( | ecx_contextt * | context, |
| const ec_errort * | Ec | ||
| ) |
Pushes an error on the error list.
| [in] | context | = context struct |
| [in] | Ec | pointer describing the error. |
|
static |
Push index of segmented LRD/LWR/LRW combination.
| [in] | context | = context struct |
| [in] | idx | = Used datagram index. |
| [in] | data | = Pointer to process data segment. |
| [in] | length | = Length of data segment in bytes. |
| uint32 ecx_readeeprom | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| uint16 | eeproma, | ||
| int | timeout | ||
| ) |
Read EEPROM from slave bypassing cache.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [in] | eeproma | = (WORD) Address in the EEPROM |
| [in] | timeout | = Timeout in us. |
| void ecx_readeeprom1 | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| uint16 | eeproma | ||
| ) |
Read EEPROM from slave bypassing cache. Parallel read step 1, make request to slave.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [in] | eeproma | = (WORD) Address in the EEPROM |
| uint32 ecx_readeeprom2 | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| int | timeout | ||
| ) |
Read EEPROM from slave bypassing cache. Parallel read step 2, actual read from slave.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [in] | timeout | = Timeout in us. |
| uint64 ecx_readeepromAP | ( | ecx_contextt * | context, |
| uint16 | aiadr, | ||
| uint16 | eeproma, | ||
| int | timeout | ||
| ) |
Read EEPROM from slave bypassing cache. APRD method.
| [in] | context | = context struct |
| [in] | aiadr | = auto increment address of slave |
| [in] | eeproma | = (WORD) Address in the EEPROM |
| [in] | timeout | = Timeout in us. |
| uint64 ecx_readeepromFP | ( | ecx_contextt * | context, |
| uint16 | configadr, | ||
| uint16 | eeproma, | ||
| int | timeout | ||
| ) |
Read EEPROM from slave bypassing cache. FPRD method.
| [in] | context | = context struct |
| [in] | configadr | = configured address of slave |
| [in] | eeproma | = (WORD) Address in the EEPROM |
| [in] | timeout | = Timeout in us. |
| int ecx_readstate | ( | ecx_contextt * | context | ) |
Read all slave states in ec_slave.
| [in] | context | = context struct |
| int ecx_receive_processdata | ( | ecx_contextt * | context, |
| int | timeout | ||
| ) |
| 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.
| [in] | context | = context struct |
| [in] | group | = group number |
| [in] | timeout | = Timeout in us. |
| int ecx_send_processdata | ( | ecx_contextt * | context | ) |
| 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.
| [in] | context | = context struct |
| [in] | group | = group number |
| int16 ecx_siifind | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| uint16 | cat | ||
| ) |
Find SII section header in slave EEPROM.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [in] | cat | = section category |
| uint16 ecx_siiFMMU | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| ec_eepromFMMUt * | FMMU | ||
| ) |
Get FMMU data from SII FMMU section in slave EEPROM.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [out] | FMMU | = FMMU struct from SII, max. 4 FMMU's |
| 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 capabillities the request is 4 or 8 bytes.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [in] | address | = eeprom address in bytes (slave uses words) |
| int ecx_siiPDO | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| ec_eepromPDOt * | PDO, | ||
| uint8 | t | ||
| ) |
Get PDO data from SII PDO section in slave EEPROM.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [out] | PDO | = PDO struct from SII |
| [in] | t | = 0=RXPDO 1=TXPDO |
| uint16 ecx_siiSM | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| ec_eepromSMt * | SM | ||
| ) |
Get SM data from SII SM section in slave EEPROM.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [out] | SM | = first SM struct from SII |
| uint16 ecx_siiSMnext | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| ec_eepromSMt * | SM, | ||
| uint16 | n | ||
| ) |
Get next SM data from SII SM section in slave EEPROM.
| [in] | context | = context struct |
| [in] | slave | = slave number |
| [out] | SM | = first SM struct from SII |
| [in] | n | = SM number |
| void ecx_siistring | ( | ecx_contextt * | context, |
| char * | str, | ||
| uint16 | slave, | ||
| uint16 | Sn | ||
| ) |
Get string from SII string section in slave EEPROM.
| [in] | context | = context struct |
| [out] | str | = requested string, 0x00 if not found |
| [in] | slave | = slave number |
| [in] | Sn | = string number |
| uint16 ecx_statecheck | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| uint16 | reqstate, | ||
| int | timeout | ||
| ) |
Check actual slave state. This is a blocking function.
| [in] | context | = context struct |
| [in] | slave | = Slave number, 0 = all slaves |
| [in] | reqstate | = Requested state |
| [in] | timeout | = Timout value in us |
| int ecx_writeeeprom | ( | ecx_contextt * | context, |
| uint16 | slave, | ||
| uint16 | eeproma, | ||
| uint16 | data, | ||
| int | timeout | ||
| ) |
Write EEPROM to slave bypassing cache.
| [in] | context | = context struct |
| [in] | slave | = Slave number |
| [in] | eeproma | = (WORD) Address in the EEPROM |
| [in] | data | = 16bit data |
| [in] | timeout | = Timeout in us. |
| int ecx_writeeepromAP | ( | ecx_contextt * | context, |
| uint16 | aiadr, | ||
| uint16 | eeproma, | ||
| uint16 | data, | ||
| int | timeout | ||
| ) |
Write EEPROM to slave bypassing cache. APWR method.
| [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. |
| int ecx_writeeepromFP | ( | ecx_contextt * | context, |
| uint16 | configadr, | ||
| uint16 | eeproma, | ||
| uint16 | data, | ||
| int | timeout | ||
| ) |
Write EEPROM to slave bypassing cache. FPWR method.
| [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. |
| 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.
| [in] | context | = context struct |
| [in] | slave | = Slave number, 0 = master |
| int64 ec_DCtime |
|
static |
current slave for EEPROM cache buffer
|
static |
buffer for EEPROM FMMU data
| ec_groupt ec_group[EC_MAXGROUP] |
slave group structure
|
static |
|
static |
PDO assign struct to store data of one slave
|
static |
PDO description struct to store data of one slave
| PACKED_END ec_slavet ec_slave[EC_MAXSLAVE] |
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().
| int ec_slavecount |
number of slaves found on the network
|
static |
buffer for EEPROM SM data
|
static |
SyncManager Communication Type struct to store data of one slave
| boolean EcatError = FALSE |
Global variable TRUE if error available in error stack
| ecx_contextt ecx_context |
| ecx_portt ecx_port |
| ecx_redportt ecx_redport |
|
static |
cache for EEPROM read functions
|
static |
bitmap for filled cache buffer bytes
1.8.3.1