Merge pull request #303 from OpenEtherCATsociety/feature/soem_140

Feature/soem 140
This commit is contained in:
ArthurKetels 2019-06-12 19:25:55 +02:00 committed by GitHub
commit e2fc362539
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
20 changed files with 456 additions and 217 deletions

View File

@ -32,7 +32,7 @@ PROJECT_NAME = SOEM
# This could be handy for archiving the generated documentation or
# if some version control system is used.
PROJECT_NUMBER = v1.3.3
PROJECT_NUMBER = v1.4.0
# Using the PROJECT_BRIEF tag one can provide an optional one line description
# for a project that appears at the top of each page and should give viewer

BIN
doc/images/legacy_iomap.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

View File

@ -114,6 +114,13 @@
* - Error messages updated to latest ETG1020 document.
* - FoE transfers now support busy response.
*
* Features as of 1.4.0 :
*
* Added ERIKA target.
* Added macOS target.
* Support for EoE over existing mailbox API.
*
*
* \section build Build instructions
*
* See README.md in the root folder.
@ -187,6 +194,9 @@
* - Added rtems target.
* - Added support for overlapping IOmap.
*
* Version 1.4.0 : 2019-05
* - Various fixes and improvements
*
* \section legal Legal notice
*
* Licensed under the GNU General Public License version 2 with exceptions. See

View File

@ -5,7 +5,7 @@
The SOEM is a library that provides the user application with the means to send
and receive EtherCAT frames. It is up to the application to provide means for:
- Reading and writing process data to be sent/received by SOEM
- Keeping local IO data synchronised with the global IOmap
- Keeping local IO data synchronized with the global IOmap
- Detecting errors reported by SOEM
- Managing errors reported by SOEM
@ -150,6 +150,122 @@ handling is split into ec_send_processdata and ec_receive_processdata.
- Now we have a system up and running, all slaves are in state operational.
\section configuration_custom Custom Configuration
\subsection iomap_config PDO Assign and PDO Config
Do custom configuration with PDO Assign or PDO Config. SOEM support custom configuration during start via a
PreOP to SafeOP configuration hook. It can be done per slave and should be set before calling
the configuration and mapping of process data, e.g. the call to ec_config_map. Setting the configuration
hook ensure that the custom configuration will be applied when calling recover and re-configuration
of a slave, as described below.
\code
int EL7031setup(uint16 slave)
{
int retval;
uint16 u16val;
retval = 0;
/* Map velocity PDO assignment via Complete Access*/
uint16 map_1c12[4] = {0x0003, 0x1601, 0x1602, 0x1604};
uint16 map_1c13[3] = {0x0002, 0x1a01, 0x1a03};
retval += ec_SDOwrite(slave, 0x1c12, 0x00, TRUE, sizeof(map_1c12), &map_1c12, EC_TIMEOUTSAFE);
retval += ec_SDOwrite(slave, 0x1c13, 0x00, TRUE, sizeof(map_1c13), &map_1c13, EC_TIMEOUTSAFE);
/* set some motor parameters, just as example */
u16val = 1200; // max motor current in mA
retval += ec_SDOwrite(slave, 0x8010, 0x01, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTSAFE);
u16val = 150; // motor coil resistance in 0.01ohm
retval += ec_SDOwrite(slave, 0x8010, 0x04, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTSAFE);
/* set other necessary parameters as needed */
...
printf("EL7031 slave %d set, retval = %d\n", slave, retval);
return 1;
}
void simpletest(char *ifname)
{
...
/* Detect slave beckhoff EL7031 from vendor ID and product code */
if((ec_slave[slc].eep_man == 0x00000002) && (ec_slave[slc].eep_id == 0x1b773052))
{
printf("Found %s at position %d\n", ec_slave[slc].name, slc);
/* link slave specific setup to preop->safeop hook */
ec_slave[slc].PO2SOconfig = EL7031setup;
}
...
\endcode
\subsection iomap_layout Legacy versus overlapping IOmap
IOmap options legacy versus overlapping. Overlapping IOmap was introduced to handle
the TI ESC that doesn't support RW access to non-interleaved input and output process
data of multiple slaves. The difference is that legacy IOmapping will send IOmap as is
on the EtherCAT network while the overlapping will re-use logic addressing per slave to
replace RxPDO process data coming from the Master with TxPDO process data generated by the slave
sent back to the master.
Overview of legacy pdo map
\image html legacy_iomap.png "Legacy IOmapping"
\image latex legacy_iomap.png "Legacy IOmapping" width=15cm
Overview of overlapping pdo map
\image html overlapping_iomap.png "Overlapping IOmapping"
\image latex overlapping_iomap.png "Overlapping IOmapping" width=15cm
\subsection iomap_groups EtherCAT slave groups
Slave groups can be used to group slaves into separate logic groups within an EtherCAT network.
Each group will have its own logic address space mapped to an IOmap address and make it possible to
send and receive process data at different update rate.
Below is an example on how to assign a slave to a group. <b>OBS!</b> A slave can only be member in one group.
\code
for (cnt = 1; cnt <= ec_slavecount; cnt++)
{
if ( <some condition> )
{
ec_slave[cnt].group = <X>;
}
else
{
ec_slave[cnt].group = <Y>;
}
}
\endcode
Alternative 1, configure all slave groups at once, call ec_config_map or ec_config_map_group with arg 0.
This option will share IOmap and store the group IOmap data at offset EC_LOGGROUPOFFSET.
\code
ec_config_map_group(&IOmap, 0);
\endcode
Alternative 2, configure the slave groups one by one, call ec_config_map or ec_config_map_group with arg <X>, <Y>.
This option will use different, supplied by the user, IOmaps.
\code
ec_config_map_group(&IOmap1, <X>);
ec_config_map_group(&IOmap2, <Y>);
\endcode
To exchange process data for given group(s) the user must call send/recv process data per group.
The send and receive stack of process data don't consider groups, so the application has to send
and receive the process data for one group before sending/receiving process data for another group.
\code
ec_send_processdata_group(<X>);
ec_receive_processdata_group(<X>, EC_TIMEOUTRET);
ec_send_processdata_group(<Y>);
ec_receive_processdata_group(<Y>, EC_TIMEOUTRET);
\endcode
\section application Application
\subsection iomap Accessing data through IOmap

View File

@ -15,9 +15,13 @@ extern "C"
#include <stdint.h>
/* General types */
typedef uint8_t boolean;
#ifndef TRUE
#define TRUE 1
#endif
#ifndef FALSE
#define FALSE 0
#endif
typedef uint8_t boolean;
typedef int8_t int8;
typedef int16_t int16;
typedef int32_t int32;

View File

@ -72,10 +72,14 @@ int osal_usleep (uint32 usec)
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
{
struct timespec ts;
int return_value;
(void)tz; /* Not used */
return_value = gettimeofday(tv, tz);
/* Use clock_gettime CLOCK_MONOTONIC to a avoid NTP time adjustments */
return_value = clock_gettime(CLOCK_MONOTONIC, &ts);
tv->tv_sec = ts.tv_sec;
tv->tv_usec = ts.tv_nsec / 1000;
return return_value;
}

View File

@ -31,11 +31,14 @@
* This layer if fully transparent for the higher layers.
*/
#include <vxWorks.h>
#include <ctype.h>
#include <string.h>
#include <stdio.h>
#include <muxLib.h>
#include <ipProto.h>
#include <vxWorks.h>
#include <wvLib.h>
#include <sysLib.h>
#include "oshw.h"
#include "osal.h"
@ -96,6 +99,10 @@ const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
/** second MAC word is used for identification */
#define RX_SEC secMAC[1]
/* usec per tick for timeconversion, default to 1kHz */
#define USECS_PER_SEC 1000000
static unsigned int usec_per_tick = 1000;
/** Receive hook called by Mux driver. */
static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg);
@ -126,6 +133,11 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
int unit_no = -1;
ETHERCAT_PKT_DEV * pPktDev;
/* Get systick info, sysClkRateGet return ticks per second */
usec_per_tick = USECS_PER_SEC / sysClkRateGet();
/* Don't allow 0 since it is used in DIV */
if(usec_per_tick == 0)
usec_per_tick = 1;
/* Make reference to packet device struct, keep track if the packet
* device is the redundant or not.
*/
@ -146,7 +158,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
pPktDev->overrun_count = 0;
/* Create multi-thread support semaphores */
port->sem_get_index = semBCreate(SEM_Q_FIFO, SEM_FULL);
port->sem_get_index = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE);
/* Get the dev name and unit from ifname
* We assume form gei1, fei0...
@ -172,13 +184,22 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
* as user reference
*/
/* Bind to mux */
pPktDev->pCookie = muxBind(ifn, unit_no, mux_rx_callback, NULL, NULL, NULL, MUX_PROTO_SNARF, "ECAT SNARF", pPktDev);
pPktDev->pCookie = muxBind(ifn,
unit_no,
mux_rx_callback,
NULL,
NULL,
NULL,
MUX_PROTO_SNARF,
"ECAT SNARF",
pPktDev);
if (pPktDev->pCookie == NULL)
{
/* fail */
NIC_LOGMSG("ecx_setupnic: muxBind init for gei: %d failed\n", unit_no, 2, 3, 4, 5, 6);
goto exit;
/* fail */
NIC_LOGMSG("ecx_setupnic: muxBind init for gei: %d failed\n",
unit_no, 2, 3, 4, 5, 6);
goto exit;
}
/* Get reference tp END obje */
@ -186,10 +207,10 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
if (port->pktDev.endObj == NULL)
{
/* fail */
NIC_LOGMSG("error_hook: endFindByName failed, device gei: %d not found\n",
unit_no, 2, 3, 4, 5, 6);
goto exit;
/* fail */
NIC_LOGMSG("error_hook: endFindByName failed, device gei: %d not found\n",
unit_no, 2, 3, 4, 5, 6);
goto exit;
}
if (secondary)
@ -236,13 +257,13 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
/* Create mailboxes for each potential EtherCAT frame index */
for (i = 0; i < EC_MAXBUF; i++)
{
port->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
if (port->msgQId[i] == MSG_Q_ID_NULL)
{
NIC_LOGMSG("ecx_setupnic: Failed to create MsgQ[%d]",
i, 2, 3, 4, 5, 6);
goto exit;
}
port->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
if (port->msgQId[i] == MSG_Q_ID_NULL)
{
NIC_LOGMSG("ecx_setupnic: Failed to create MsgQ[%d]",
i, 2, 3, 4, 5, 6);
goto exit;
}
}
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
}
@ -271,20 +292,31 @@ int ecx_closenic(ecx_portt *port)
{
int i;
ETHERCAT_PKT_DEV * pPktDev;
M_BLK_ID trash_can;
pPktDev = &(port->pktDev);
for (i = 0; i < EC_MAXBUF; i++)
{
if (port->msgQId[i] != MSG_Q_ID_NULL)
{
msgQDelete(port->msgQId[i]);
if (port->msgQId[i] != MSG_Q_ID_NULL)
{
if (msgQReceive(port->msgQId[i],
(char *)&trash_can,
sizeof(M_BLK_ID),
NO_WAIT) != ERROR)
{
NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
2, 3, 4, 5, 6);
/* Free resources */
netMblkClChainFree(trash_can);
}
msgQDelete(port->msgQId[i]);
}
}
if (pPktDev->pCookie != NULL)
{
muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
}
/* Clean redundant resources if available*/
@ -295,6 +327,16 @@ int ecx_closenic(ecx_portt *port)
{
if (port->redport->msgQId[i] != MSG_Q_ID_NULL)
{
if (msgQReceive(port->redport->msgQId[i],
(char *)&trash_can,
sizeof(M_BLK_ID),
NO_WAIT) != ERROR)
{
NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
2, 3, 4, 5, 6);
/* Free resources */
netMblkClChainFree(trash_can);
}
msgQDelete(port->redport->msgQId[i]);
}
}
@ -333,8 +375,6 @@ int ecx_getindex(ecx_portt *port)
{
int idx;
int cnt;
MSG_Q_ID msgQId;
M_BLK_ID trash_can;
semTake(port->sem_get_index, WAIT_FOREVER);
@ -356,27 +396,6 @@ int ecx_getindex(ecx_portt *port)
}
}
port->rxbufstat[idx] = EC_BUF_ALLOC;
/* Clean up any abandoned frames */
msgQId = port->msgQId[idx];
if (msgQReceive(msgQId, (char *)&trash_can, sizeof(M_BLK_ID), NO_WAIT) == OK)
{
/* Free resources */
netMblkClChainFree(trash_can);
}
if (port->redstate != ECT_RED_NONE)
{
port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
/* Clean up any abandoned frames */
msgQId = port->redport->msgQId[idx];
if (msgQReceive(msgQId, (char *)&trash_can, sizeof(M_BLK_ID), NO_WAIT) == OK)
{
/* Free resources */
netMblkClChainFree(trash_can);
}
}
port->lastidx = idx;
semGive(port->sem_get_index);
@ -399,34 +418,58 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
/** Low level transmit buffer over mux layer 2 driver
*
* @param[in] pPktDev = packet device to send buffer over
* @param[in] idx = index in tx buffer array
* @param[in] buf = buff to send
* @param[in] len = bytes to send
* @return driver send result
*/
static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, void * buf, int len)
static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, int idx, void * buf, int len)
{
STATUS status = OK;
M_BLK_ID pPacket;
int rval = 0;
STATUS status = OK;
M_BLK_ID pPacket = NULL;
int rval = 0;
END_OBJ *endObj = (END_OBJ *)pPktDev->endObj;
MSG_Q_ID msgQId;
/* Allocate m_blk to send */
if ((pPacket = netTupleGet(pPktDev->endObj->pNetPool,
len,
M_DONTWAIT,
MT_DATA,
TRUE)) == NULL)
/* Clean up any abandoned frames and re-use the allocated buffer*/
msgQId = pPktDev->port->msgQId[idx];
if(msgQNumMsgs(msgQId) > 0)
{
NIC_LOGMSG("ec_outfram_send: Could not allocate MBLK memory!\n", 1, 2, 3, 4, 5, 6);
return ERROR;
pPktDev->abandoned_count++;
NIC_LOGMSG("ec_outfram_send: idx %d MsgQ abandoned\n", idx,
2, 3, 4, 5, 6);
if (msgQReceive(msgQId,
(char *)&pPacket,
sizeof(M_BLK_ID),
NO_WAIT) == ERROR)
{
pPacket = NULL;
NIC_LOGMSG("ec_outfram_send: idx %d MsgQ mBlk handled by receiver\n", idx,
2, 3, 4, 5, 6);
}
}
if (pPacket == NULL)
{
/* Allocate m_blk to send */
if ((pPacket = netTupleGet(endObj->pNetPool,
len,
M_DONTWAIT,
MT_DATA,
TRUE)) == NULL)
{
NIC_LOGMSG("ec_outfram_send: Could not allocate MBLK memory!\n", 1, 2, 3, 4, 5, 6);
return ERROR;
}
}
pPacket->mBlkHdr.mLen = len;
pPacket->mBlkHdr.mFlags |= M_HEADER;
pPacket->mBlkHdr.mFlags |= M_PKTHDR;
pPacket->mBlkHdr.mData = pPacket->pClBlk->clNode.pClBuf;
pPacket->mBlkPktHdr.len = len;
pPacket->mBlkPktHdr.len = pPacket->m_len;
netMblkFromBufCopy(pPacket, buf, 0, pPacket->mBlkHdr.mLen, M_DONTWAIT, NULL);
status = muxTkSend(pPktDev->pCookie, pPacket, NULL, htons(ETH_P_ECAT), NULL);
status = muxSend(endObj, pPacket);
if (status == OK)
{
@ -475,7 +518,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
}
(*stack->rxbufstat)[idx] = EC_BUF_TX;
rval = ec_outfram_send(pPktDev, (char*)(*stack->txbuf)[idx],
rval = ec_outfram_send(pPktDev, idx, (char*)(*stack->txbuf)[idx],
(*stack->txbuflength)[idx]);
if (rval > 0)
{
@ -516,7 +559,7 @@ int ecx_outframe_red(ecx_portt *port, int idx)
ehp->sa1 = htons(secMAC[1]);
/* transmit over secondary interface */
port->redport->rxbufstat[idx] = EC_BUF_TX;
rval = ec_outfram_send(&(port->redport->pktDev), &(port->txbuf2), port->txbuflength2);
rval = ec_outfram_send(&(port->redport->pktDev), idx, &(port->txbuf2), port->txbuflength2);
if (rval <= 0)
{
port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
@ -545,77 +588,85 @@ static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO
MSG_Q_ID msgQId;
ETHERCAT_PKT_DEV * pPktDev;
int length;
int bufstat;
/* check if it is an EtherCAT frame */
if (type == ETH_P_ECAT)
{
length = pMblk->mBlkHdr.mLen;
tempbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
pPktDev = (ETHERCAT_PKT_DEV *)muxUserArg;
port = pPktDev->port;
length = pMblk->mBlkHdr.mLen;
tempbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
pPktDev = (ETHERCAT_PKT_DEV *)muxUserArg;
port = pPktDev->port;
/* Get ethercat frame header */
ecp = (ec_comt*)&(*tempbuf)[ETH_HEADERSIZE];
idxf = ecp->index;
if (idxf >= EC_MAXBUF)
{
NIC_LOGMSG("mux_rx_callback: idx %d out of bounds\n", idxf,
2, 3, 4, 5, 6);
return ret;
}
/* Get ethercat frame header */
ecp = (ec_comt*)&(*tempbuf)[ETH_HEADERSIZE];
idxf = ecp->index;
if (idxf >= EC_MAXBUF)
{
NIC_LOGMSG("mux_rx_callback: idx %d out of bounds\n", idxf,
2, 3, 4, 5, 6);
return ret;
}
/* Check if it is the redundant port or not */
if (pPktDev->redundant == 1)
{
msgQId = port->redport->msgQId[idxf];
}
else
{
msgQId = port->msgQId[idxf];
}
/* Check if it is the redundant port or not */
if (pPktDev->redundant == 1)
{
bufstat = port->redport->rxbufstat[idxf];
msgQId = port->redport->msgQId[idxf];
}
else
{
bufstat = port->rxbufstat[idxf];
msgQId = port->msgQId[idxf];
}
if (length > 0)
{
/* Post the frame to the reqceive Q for the EtherCAT stack */
STATUS status;
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
NO_WAIT, MSG_PRI_NORMAL);
/* Check length and if someone expects the frame */
if (length > 0 && bufstat == EC_BUF_TX)
{
/* Post the frame to the receive Q for the EtherCAT stack */
STATUS status;
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
NO_WAIT, MSG_PRI_NORMAL);
if (status == OK)
{
NIC_WVEVENT(ECAT_RECV_OK, (char *)&length, sizeof(length));
ret = TRUE;
}
else if ((status == ERROR) && (errno == S_objLib_OBJ_UNAVAILABLE))
{
/* Try to empty the MSGQ since we for some strange reason
* already have a frame in the MsqQ,
* is it due to timeout when receiving?
* We want the latest received frame in the buffer
*/
port->pktDev.overrun_count++;
NIC_LOGMSG("mux_rx_callback: idx %d MsgQ overrun\n", idxf,
2, 3, 4, 5, 6);
M_BLK_ID trash_can;
if (msgQReceive(msgQId,
(char *)&trash_can,
sizeof(M_BLK_ID),
NO_WAIT) != ERROR)
{
/* Free resources */
netMblkClChainFree(trash_can);
}
status = msgQSend(msgQId,
(char *)&pMblk,
sizeof(M_BLK_ID),
NO_WAIT,
MSG_PRI_NORMAL);
if (status == OK)
{
NIC_WVEVENT(ECAT_RECV_OK, (char *)&length, sizeof(length));
ret = TRUE;
NIC_WVEVENT(ECAT_RECV_RETRY_OK, (char *)&length, sizeof(length));
ret = TRUE;
}
else if ((status == ERROR) && (errno == S_objLib_OBJ_UNAVAILABLE))
{
/* Try to empty the MSGQ since we for some strange reason
* already have a frame in the MsqQ,
* is it due to timeout when receiving?
* We want the latest received frame in the buffer
*/
port->pktDev.overrun_count++;
NIC_LOGMSG("mux_rx_callback: idx %d MsgQ overrun\n", idxf,
2, 3, 4, 5, 6);
M_BLK_ID trash_can;
if (msgQReceive(msgQId, (char *)&trash_can,
sizeof(M_BLK_ID), NO_WAIT) == OK)
{
/* Free resources */
netMblkClChainFree(trash_can);
}
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
NO_WAIT, MSG_PRI_NORMAL);
if (status == OK)
{
NIC_WVEVENT(ECAT_RECV_RETRY_OK, (char *)&length, sizeof(length));
ret = TRUE;
}
}
else
{
NIC_WVEVENT(ECAT_RECV_FAILED, (char *)&length, sizeof(length));
}
}
}
else
{
NIC_WVEVENT(ECAT_RECV_FAILED, (char *)&length, sizeof(length));
}
}
}
return ret;
@ -631,7 +682,7 @@ static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID * pMb
{
int bytesrx = 0;
MSG_Q_ID msgQId;
int tick_timeout = max((timeout / 1000), 1);
int tick_timeout = max((timeout / usec_per_tick), 1);
if (stacknumber == 1)
{
@ -912,9 +963,9 @@ int ec_outframe_red(int idx)
return ecx_outframe_red(&ecx_port, idx);
}
int ec_inframe(int idx, int stacknumber)
int ec_inframe(int idx, int stacknumber, int timeout)
{
return ecx_inframe(&ecx_port, idx, stacknumber);
return ecx_inframe(&ecx_port, idx, stacknumber, timeout);
}
int ec_waitinframe(int idx, int timeout)

View File

@ -17,18 +17,18 @@ extern "C"
#endif
#include <vxWorks.h>
#include <muxLib.h>
/** structure to connect EtherCAT stack and VxWorks device */
typedef struct ETHERCAT_PKT_DEV
{
struct ecx_port *port;
void *pCookie;
END_OBJ *endObj;
void *endObj;
UINT32 redundant;
UINT32 tx_count;
UINT32 rx_count;
UINT32 overrun_count;
UINT32 abandoned_count;
}ETHERCAT_PKT_DEV;
/** pointer structure to Tx and Rx stacks */

View File

@ -142,7 +142,7 @@ int ecx_detect_slaves(ecx_contextt *context)
{
EC_PRINT("Error: too many slaves on network: num_slaves=%d, EC_MAXSLAVE=%d\n",
wkc, EC_MAXSLAVE);
return -2;
return EC_SLAVECOUNTEXCEEDED;
}
}
return wkc;
@ -589,8 +589,16 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
}
/* some slaves need eeprom available to PDI in init->preop transition */
ecx_eeprom2pdi(context, slave);
/* request pre_op for slave */
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_PRE_OP | EC_STATE_ACK) , EC_TIMEOUTRET3); /* set preop status */
/* User may override automatic state change */
if (context->manualstatechange == 0)
{
/* request pre_op for slave */
ecx_FPWRw(context->port,
configadr,
ECT_REG_ALCTL,
htoes(EC_STATE_PRE_OP | EC_STATE_ACK),
EC_TIMEOUTRET3); /* set preop status */
}
}
}
return wkc;
@ -645,6 +653,10 @@ static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
{
context->slavelist[slave].PO2SOconfig(slave);
}
if (context->slavelist[slave].PO2SOconfigx) /* only if registered */
{
context->slavelist[slave].PO2SOconfigx(context, slave);
}
/* if slave not found in configlist find IO mapping in slave self */
if (!context->slavelist[slave].configindex)
{
@ -1269,8 +1281,16 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
}
ecx_eeprom2pdi(context, slave); /* set Eeprom control to PDI */
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP) , EC_TIMEOUTRET3); /* set safeop status */
/* User may override automatic state change */
if (context->manualstatechange == 0)
{
/* request safe_op for slave */
ecx_FPWRw(context->port,
configadr,
ECT_REG_ALCTL,
htoes(EC_STATE_SAFE_OP),
EC_TIMEOUTRET3); /* set safeop status */
}
if (context->slavelist[slave].blockLRW)
{
context->grouplist[group].blockLRW++;
@ -1405,8 +1425,16 @@ int ecx_config_overlap_map_group(ecx_contextt *context, void *pIOmap, uint8 grou
}
ecx_eeprom2pdi(context, slave); /* set Eeprom control to PDI */
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP), EC_TIMEOUTRET3); /* set safeop status */
/* User may override automatic state change */
if (context->manualstatechange == 0)
{
/* request safe_op for slave */
ecx_FPWRw(context->port,
configadr,
ECT_REG_ALCTL,
htoes(EC_STATE_SAFE_OP),
EC_TIMEOUTRET3);
}
if (context->slavelist[slave].blockLRW)
{
context->grouplist[group].blockLRW++;

View File

@ -119,7 +119,8 @@ ecx_contextt ecx_context = {
&ec_SM, // .eepSM =
&ec_FMMU, // .eepFMMU =
NULL, // .FOEhook()
NULL // .EOEhook()
NULL, // .EOEhook()
0 // .manualstatechange
};
#endif
@ -1097,7 +1098,8 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
}
else /* no read mailbox available */
{
wkc = 0;
if (wkc > 0)
wkc = EC_TIMEOUT;
}
}

View File

@ -100,6 +100,8 @@ PACKED_END
#define EC_SMENABLEMASK 0xfffeffff
typedef struct ecx_context ecx_contextt;
/** for list of ethercat slaves detected */
typedef struct ec_slave
{
@ -225,8 +227,10 @@ typedef struct ec_slave
uint8 FMMUunused;
/** Boolean for tracking whether the slave is (not) responding, not used/set by the SOEM library */
boolean islost;
/** registered configuration function PO->SO */
/** registered configuration function PO->SO, (DEPRECATED)*/
int (*PO2SOconfig)(uint16 slave);
/** registered configuration function PO->SO */
int (*PO2SOconfigx)(ecx_contextt * context, uint16 slave);
/** readable name */
char name[EC_MAXNAME + 1];
} ec_slavet;
@ -377,7 +381,6 @@ typedef struct PACKED ec_PDOdesc
PACKED_END
/** Context structure , referenced by all ecx functions*/
typedef struct ecx_context ecx_contextt;
struct ecx_context
{
/** port reference, may include red_port */
@ -424,6 +427,8 @@ struct ecx_context
int (*FOEhook)(uint16 slave, int packetnumber, int datasize);
/** registered EoE hook */
int (*EOEhook)(ecx_contextt * context, uint16 slave, void * eoembx);
/** flag to control legacy automatic state change or manual state change */
int manualstatechange;
};
#ifdef EC_VER1

View File

@ -291,6 +291,63 @@ char* ec_mbxerror2string( uint16 errorcode)
return (char *) ec_mbxerrorlist[i].errordescription;
}
/** Convert an error to text string.
*
* @param[in] Ec = Struct describing the error.
* @return readable string
*/
char* ecx_err2string(const ec_errort Ec)
{
char timestr[20];
sprintf(timestr, "Time:%12.3f", Ec.Time.sec + (Ec.Time.usec / 1000000.0) );
switch (Ec.Etype)
{
case EC_ERR_TYPE_SDO_ERROR:
{
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
break;
}
case EC_ERR_TYPE_EMERGENCY:
{
sprintf(estring, "%s EMERGENCY slave:%d error:%4.4x\n",
timestr, Ec.Slave, Ec.ErrorCode);
break;
}
case EC_ERR_TYPE_PACKET_ERROR:
{
sprintf(estring, "%s PACKET slave:%d index:%4.4x.%2.2x error:%d\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, Ec.ErrorCode);
break;
}
case EC_ERR_TYPE_SDOINFO_ERROR:
{
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
break;
}
case EC_ERR_TYPE_SOE_ERROR:
{
sprintf(estring, "%s SoE slave:%d IDN:%4.4x error:%4.4x %s\n",
timestr, Ec.Slave, Ec.Index, (unsigned)Ec.AbortCode, ec_soeerror2string(Ec.ErrorCode));
break;
}
case EC_ERR_TYPE_MBX_ERROR:
{
sprintf(estring, "%s MBX slave:%d error:%4.4x %s\n",
timestr, Ec.Slave, Ec.ErrorCode, ec_mbxerror2string(Ec.ErrorCode));
break;
}
default:
{
sprintf(estring, "%s error:%8.8x\n",
timestr, (unsigned)Ec.AbortCode);
break;
}
}
return (char*) estring;
}
/** Look up error in ec_errorlist and convert to text string.
*
* @param[in] context = context struct
@ -299,57 +356,10 @@ char* ec_mbxerror2string( uint16 errorcode)
char* ecx_elist2string(ecx_contextt *context)
{
ec_errort Ec;
char timestr[20];
if (ecx_poperror(context, &Ec))
{
sprintf(timestr, "Time:%12.3f", Ec.Time.sec + (Ec.Time.usec / 1000000.0) );
switch (Ec.Etype)
{
case EC_ERR_TYPE_SDO_ERROR:
{
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
break;
}
case EC_ERR_TYPE_EMERGENCY:
{
sprintf(estring, "%s EMERGENCY slave:%d error:%4.4x\n",
timestr, Ec.Slave, Ec.ErrorCode);
break;
}
case EC_ERR_TYPE_PACKET_ERROR:
{
sprintf(estring, "%s PACKET slave:%d index:%4.4x.%2.2x error:%d\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, Ec.ErrorCode);
break;
}
case EC_ERR_TYPE_SDOINFO_ERROR:
{
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
break;
}
case EC_ERR_TYPE_SOE_ERROR:
{
sprintf(estring, "%s SoE slave:%d IDN:%4.4x error:%4.4x %s\n",
timestr, Ec.Slave, Ec.Index, (unsigned)Ec.AbortCode, ec_soeerror2string(Ec.ErrorCode));
break;
}
case EC_ERR_TYPE_MBX_ERROR:
{
sprintf(estring, "%s MBX slave:%d error:%4.4x %s\n",
timestr, Ec.Slave, Ec.ErrorCode, ec_mbxerror2string(Ec.ErrorCode));
break;
}
default:
{
sprintf(estring, "%s error:%8.8x\n",
timestr, (unsigned)Ec.AbortCode);
break;
}
}
return (char*) estring;
return ecx_err2string(Ec);
}
else
{

View File

@ -19,6 +19,8 @@ extern "C"
char* ec_sdoerror2string( uint32 sdoerrorcode);
char* ec_ALstatuscode2string( uint16 ALstatuscode);
char* ec_soeerror2string( uint16 errorcode);
char* ec_mbxerror2string( uint16 errorcode);
char* ecx_err2string(const ec_errort Ec);
char* ecx_elist2string(ecx_contextt *context);
#ifdef EC_VER1

View File

@ -23,23 +23,30 @@ extern "C"
{
#endif
/** define EC_VER1 if version 1 default context and functions are needed
* comment if application uses only ecx_ functions and own context */
#define EC_VER1
#include "osal.h"
/** define EC_VER1 if version 1 default context and functions are needed
* define EC_VER2 if application uses only ecx_ functions and own context */
#if !defined(EC_VER1) && !defined(EC_VER2)
# define EC_VER1
#endif
/** Define little endian target by default if no endian is set */
#if !defined(EC_LITTLE_ENDIAN) && !defined(EC_BIG_ENDIAN)
# define EC_LITTLE_ENDIAN
#endif
/** return value general error */
#define EC_ERROR -3
/** return value no frame returned */
#define EC_NOFRAME -1
#define EC_NOFRAME -1
/** return value unknown frame received */
#define EC_OTHERFRAME -2
#define EC_OTHERFRAME -2
/** return value general error */
#define EC_ERROR -3
/** return value too many slaves */
#define EC_SLAVECOUNTEXCEEDED -4
/** return value request timeout */
#define EC_TIMEOUT -5
/** maximum EtherCAT frame length in bytes */
#define EC_MAXECATFRAME 1518
/** maximum EtherCAT LRW frame length in bytes */

View File

@ -238,7 +238,7 @@ void teststarter(char *ifname)
/* request OP state for all slaves */
ec_writestate(0);
chk = 40;
chk = 200;
/* wait for all slaves to reach OP state */
do
{

View File

@ -91,7 +91,7 @@ void redtest(char *ifname, char *ifname2)
/* activate cyclic process data */
dorun = 1;
/* wait for all slaves to reach OP state */
ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
ec_statecheck(0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
oloop = ec_slave[0].Obytes;
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
if (oloop > 8) oloop = 8;

View File

@ -70,7 +70,7 @@ void simpletest(char *ifname)
ec_receive_processdata(EC_TIMEOUTRET);
/* request OP state for all slaves */
ec_writestate(0);
chk = 40;
chk = 200;
/* wait for all slaves to reach OP state */
do
{

View File

@ -81,7 +81,7 @@ void redtest(char *ifname, char *ifname2)
/* request OP state for all slaves */
ec_writestate(0);
/* wait for all slaves to reach OP state */
ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
ec_statecheck(0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
oloop = ec_slave[0].Obytes;
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
if (oloop > 8) oloop = 8;

View File

@ -186,7 +186,7 @@ void simpletest(char *ifname)
/* request OP state for all slaves */
ec_writestate(0);
chk = 40;
chk = 200;
/* wait for all slaves to reach OP state */
do
{