Merge pull request #15 from alberth/add_docs
Add docs, remove trailing whitespace
This commit is contained in:
commit
64d122c416
@ -47,7 +47,7 @@ static int64_t sysfrequency;
|
||||
static double qpc2usec;
|
||||
|
||||
#define USECS_PER_SEC 1000000
|
||||
|
||||
|
||||
int osal_gettimeofday (struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
return gettimeofday (tv, tz);
|
||||
@ -101,24 +101,24 @@ int osal_usleep(uint32 usec)
|
||||
|
||||
/* Mutex is not needed when running single threaded */
|
||||
|
||||
void osal_mtx_lock(osal_mutex_t * mtx)
|
||||
{
|
||||
void osal_mtx_lock(osal_mutex_t * mtx)
|
||||
{
|
||||
/* RtWaitForSingleObject((HANDLE)mtx, INFINITE); */
|
||||
}
|
||||
|
||||
void osal_mtx_unlock(osal_mutex_t * mtx)
|
||||
{
|
||||
}
|
||||
|
||||
void osal_mtx_unlock(osal_mutex_t * mtx)
|
||||
{
|
||||
/* RtReleaseMutex((HANDLE)mtx); */
|
||||
}
|
||||
|
||||
int osal_mtx_lock_timeout(osal_mutex_t * mtx, uint32_t time_ms)
|
||||
{
|
||||
}
|
||||
|
||||
int osal_mtx_lock_timeout(osal_mutex_t * mtx, uint32_t time_ms)
|
||||
{
|
||||
/* return RtWaitForSingleObject((HANDLE)mtx, time_ms); */
|
||||
return 0;
|
||||
}
|
||||
|
||||
osal_mutex_t * osal_mtx_create(void)
|
||||
{
|
||||
}
|
||||
|
||||
osal_mutex_t * osal_mtx_create(void)
|
||||
{
|
||||
/* return (void*)RtCreateMutex(NULL, FALSE, NULL); */
|
||||
return (void *)0;
|
||||
}
|
||||
|
@ -45,7 +45,7 @@
|
||||
#ifndef PACKED
|
||||
#ifdef _MSC_VER
|
||||
#define PACKED_BEGIN __pragma(pack(push, 1))
|
||||
#define PACKED
|
||||
#define PACKED
|
||||
#define PACKED_END __pragma(pack(pop))
|
||||
#elif defined(__GNUC__)
|
||||
#define PACKED_BEGIN
|
||||
|
@ -61,7 +61,7 @@ int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
struct timespec ts;
|
||||
int return_value;
|
||||
|
||||
|
||||
/* Use clock_gettime to prevent possible live-lock.
|
||||
* Gettimeofday uses CLOCK_REALTIME that can get NTP timeadjust.
|
||||
* If this function preempts timeadjust and it uses vpage it live-locks.
|
||||
@ -85,12 +85,12 @@ ec_timet osal_current_time(void)
|
||||
|
||||
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
|
||||
{
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
if (diff->usec < 0) {
|
||||
--diff->sec;
|
||||
diff->usec += 1000000;
|
||||
}
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
if (diff->usec < 0) {
|
||||
--diff->sec;
|
||||
diff->usec += 1000000;
|
||||
}
|
||||
}
|
||||
|
||||
void osal_timer_start(osal_timert * self, uint32 timeout_usec)
|
||||
@ -137,12 +137,12 @@ int osal_thread_create(void *thandle, int stacksize, void *func, void *param)
|
||||
int ret;
|
||||
pthread_attr_t attr;
|
||||
pthread_t *threadp;
|
||||
|
||||
|
||||
threadp = thandle;
|
||||
pthread_attr_init(&attr);
|
||||
pthread_attr_setstacksize(&attr, stacksize);
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
if(ret < 0)
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
@ -155,24 +155,24 @@ int osal_thread_create_rt(void *thandle, int stacksize, void *func, void *param)
|
||||
pthread_attr_t attr;
|
||||
struct sched_param schparam;
|
||||
pthread_t *threadp;
|
||||
|
||||
|
||||
threadp = thandle;
|
||||
pthread_attr_init(&attr);
|
||||
pthread_attr_setstacksize(&attr, stacksize);
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
pthread_attr_destroy(&attr);
|
||||
if(ret < 0)
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
memset(&schparam, 0, sizeof(schparam));
|
||||
schparam.sched_priority = 40;
|
||||
ret = pthread_setschedparam(*threadp, SCHED_FIFO, &schparam);
|
||||
if(ret < 0)
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
@ -1,32 +1,32 @@
|
||||
// ISO C9x compliant inttypes.h for Microsoft Visual Studio
|
||||
// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124
|
||||
//
|
||||
// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124
|
||||
//
|
||||
// Copyright (c) 2006 Alexander Chemeris
|
||||
//
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are met:
|
||||
//
|
||||
//
|
||||
// 1. Redistributions of source code must retain the above copyright notice,
|
||||
// this list of conditions and the following disclaimer.
|
||||
//
|
||||
//
|
||||
// 2. Redistributions in binary form must reproduce the above copyright
|
||||
// notice, this list of conditions and the following disclaimer in the
|
||||
// documentation and/or other materials provided with the distribution.
|
||||
//
|
||||
//
|
||||
// 3. The name of the author may be used to endorse or promote products
|
||||
// derived from this software without specific prior written permission.
|
||||
//
|
||||
//
|
||||
// THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
|
||||
// WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
// MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
|
||||
// EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
|
||||
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
|
||||
// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
// WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
|
||||
// OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
// ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
//
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifndef _MSC_VER // [
|
||||
|
@ -47,7 +47,7 @@ static int64_t sysfrequency;
|
||||
static double qpc2usec;
|
||||
|
||||
#define USECS_PER_SEC 1000000
|
||||
|
||||
|
||||
int osal_gettimeofday (struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
int64_t wintime, usecs;
|
||||
@ -61,7 +61,7 @@ int osal_gettimeofday (struct timeval *tv, struct timezone *tz)
|
||||
usecs = (int64_t)((double)wintime * qpc2usec);
|
||||
tv->tv_sec = (long)(usecs / 1000000);
|
||||
tv->tv_usec = (long)(usecs - (tv->tv_sec * 1000000));
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -78,12 +78,12 @@ ec_timet osal_current_time (void)
|
||||
|
||||
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
|
||||
{
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
if (diff->usec < 0) {
|
||||
--diff->sec;
|
||||
diff->usec += 1000000;
|
||||
}
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
if (diff->usec < 0) {
|
||||
--diff->sec;
|
||||
diff->usec += 1000000;
|
||||
}
|
||||
}
|
||||
|
||||
void osal_timer_start (osal_timert *self, uint32 timeout_usec)
|
||||
@ -140,7 +140,7 @@ void osal_free(void *ptr)
|
||||
int osal_thread_create(void **thandle, int stacksize, void *func, void *param)
|
||||
{
|
||||
*thandle = CreateThread(NULL, stacksize, func, param, 0, NULL);
|
||||
if(!thandle)
|
||||
if(!thandle)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
@ -66,5 +66,5 @@
|
||||
} while (0)
|
||||
|
||||
int osal_gettimeofday (struct timeval *tv, struct timezone *tz);
|
||||
|
||||
|
||||
#endif
|
||||
|
@ -1,32 +1,32 @@
|
||||
// ISO C9x compliant stdint.h for Microsoft Visual Studio
|
||||
// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124
|
||||
//
|
||||
// Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124
|
||||
//
|
||||
// Copyright (c) 2006-2008 Alexander Chemeris
|
||||
//
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are met:
|
||||
//
|
||||
//
|
||||
// 1. Redistributions of source code must retain the above copyright notice,
|
||||
// this list of conditions and the following disclaimer.
|
||||
//
|
||||
//
|
||||
// 2. Redistributions in binary form must reproduce the above copyright
|
||||
// notice, this list of conditions and the following disclaimer in the
|
||||
// documentation and/or other materials provided with the distribution.
|
||||
//
|
||||
//
|
||||
// 3. The name of the author may be used to endorse or promote products
|
||||
// derived from this software without specific prior written permission.
|
||||
//
|
||||
//
|
||||
// THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
|
||||
// WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
// MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
|
||||
// EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
|
||||
// PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
|
||||
// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
// OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||
// WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
|
||||
// OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
|
||||
// ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
//
|
||||
//
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifndef _MSC_VER // [
|
||||
|
@ -122,7 +122,7 @@ const unsigned long phy_settings = SPEED_100 | DUPLEX_FULL;
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
HPESTATUS status;
|
||||
HPEMEDIASTATUS mstat;
|
||||
@ -134,10 +134,10 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
HPE_CONFIG_OPTIONS conf = { 0, 0, NULL};
|
||||
|
||||
status = hpeOpen(ifname, phy_settings, interrupt_mode, &(port->handle));
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeOpen failed with status %04x ", status);
|
||||
if(status == E_EXIST) ECAT_PRINT_ERROR("E_EXIST\n");
|
||||
if(status == E_EXIST) ECAT_PRINT_ERROR("E_EXIST\n");
|
||||
else if(status == E_STATE) ECAT_PRINT_ERROR("E_STATE\n");
|
||||
else if(status == E_PARAM) ECAT_PRINT_ERROR("E_PARAM\n");
|
||||
else if(status == E_INVALID_ADDR) ECAT_PRINT_ERROR("E_INVALID_ADDR\n");
|
||||
@ -147,29 +147,29 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
result = 0;
|
||||
goto end;
|
||||
}
|
||||
|
||||
|
||||
conf.option_flags |= OPT_PROMISC;
|
||||
|
||||
status = hpeConfigOptions(port->handle, &conf, sizeof(conf));
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeConfigOptions failed with status %04x\n", status);
|
||||
// NOTE: HPE driver for Intel 10/100 Mbps device currently doesn't support multicast.
|
||||
result = 0;
|
||||
goto end;
|
||||
}
|
||||
|
||||
|
||||
time(&now);
|
||||
do
|
||||
do
|
||||
{
|
||||
status = hpeGetMediaStatus(port->handle, &mstat);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeGetMediaStatus failed with status %04x\n", status);
|
||||
result = 0;
|
||||
goto end;
|
||||
}
|
||||
if (mstat.media_speed == SPEED_NONE)
|
||||
if (mstat.media_speed == SPEED_NONE)
|
||||
{
|
||||
RtSleepEx(1000);
|
||||
time(&t);
|
||||
@ -177,14 +177,14 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
} while (mstat.media_speed == SPEED_NONE && t < (now+10));
|
||||
|
||||
if (((mstat.media_speed & phy_settings) == 0) || ((mstat.media_duplex & phy_settings) == 0)) {
|
||||
ECAT_PRINT_ERROR("Media not connected as requested: speed=%u, duplex=%u\n",
|
||||
ECAT_PRINT_ERROR("Media not connected as requested: speed=%u, duplex=%u\n",
|
||||
mstat.media_speed, mstat.media_duplex);
|
||||
result = 0;
|
||||
goto end;
|
||||
}
|
||||
|
||||
status= hpeGetMacAddress(port->handle, mac);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeGetMacAddress failed with status %04x\n", status);
|
||||
result = 0;
|
||||
@ -193,7 +193,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
|
||||
/* allocate 2 receive buffers and attach them */
|
||||
status = hpeAllocateReceiveBufferSet(port->handle, &(port->rx_buffers), EC_MAXBUF, EC_BUFSIZE);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeAllocateReceiveBufferSet failed with status %04x\n", status);
|
||||
result = 0;
|
||||
@ -201,7 +201,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
}
|
||||
|
||||
status = hpeAttachReceiveBufferSet(port->handle, port->rx_buffers);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
ECAT_PRINT_ERROR("hpeAttachReceiveBufferSet failed with status %04x\n", status);
|
||||
result = 0;
|
||||
@ -231,8 +231,8 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
port->stack.rxbuf = &(port->rxbuf);
|
||||
port->stack.rxbufstat = &(port->rxbufstat);
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
@ -256,7 +256,7 @@ end:
|
||||
/** Close sockets used
|
||||
* @return 0
|
||||
*/
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
HPESTATUS status;
|
||||
int i;
|
||||
@ -287,7 +287,7 @@ int ecx_closenic(ecx_portt *port)
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
void ec_setupheader(void *p)
|
||||
{
|
||||
ec_etherheadert *bp;
|
||||
bp = (ec_etherheadert *)p;
|
||||
@ -312,7 +312,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
|
||||
idx = port->lastidx + 1;
|
||||
/* index can't be larger than buffer array */
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
@ -322,17 +322,17 @@ int ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
idx++;
|
||||
cnt++;
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
}
|
||||
port->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
if ( port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
}
|
||||
|
||||
|
||||
port->lastidx = idx;
|
||||
ReleaseRtControl();
|
||||
|
||||
@ -392,7 +392,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
|
||||
log_RT_event('S',(WORD)2);
|
||||
status = hpeAttachTransmitBufferSet(port->handle, port->tx_buffers[idx]);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
result = -2;
|
||||
goto end;
|
||||
@ -400,7 +400,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
log_RT_event('S',(WORD)3);
|
||||
|
||||
status = hpeStartTransmitter(port->handle);
|
||||
if (status != E_OK)
|
||||
if (status != E_OK)
|
||||
{
|
||||
result = -3;
|
||||
goto end;
|
||||
@ -432,7 +432,7 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
datagramP = (ec_comt*)&(port->txbuf2)[ETH_HEADERSIZE];
|
||||
@ -447,8 +447,8 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
hpeAttachTransmitBufferSet(port->redport->handle, port->tx_buffers[idx]);
|
||||
status = hpeStartTransmitter(port->redport->handle);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -471,14 +471,14 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
{
|
||||
stack = &(port->redport->stack);
|
||||
}
|
||||
|
||||
|
||||
log_RT_event('R',(WORD)2);
|
||||
|
||||
status = hpeGetReceiveBuffer(port->handle, &rxbuffer);
|
||||
if (status == E_OK)
|
||||
if (status == E_OK)
|
||||
{
|
||||
memcpy(stack->tempbuf,rxbuffer->ptr, rxbuffer->used);
|
||||
bytesrx = rxbuffer->used;
|
||||
bytesrx = rxbuffer->used;
|
||||
port->tempinbufs = bytesrx;
|
||||
// TODO case no interrupt
|
||||
}
|
||||
@ -496,7 +496,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
* than requested index, store in buffer and exit. 3 frame read with matching
|
||||
* index, store in buffer, set completed flag in buffer status and exit.
|
||||
*
|
||||
*
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
@ -524,7 +524,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ( (*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
if ((idx < EC_MAXBUF) && ( (*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
{
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
@ -532,21 +532,21 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
{
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp = (ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == oshw_htons(ETH_P_ECAT))
|
||||
{
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
if (idxf == idx)
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
@ -557,7 +557,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = oshw_ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* check if index exist and someone is waiting for it */
|
||||
if (idxf < EC_MAXBUF && (*stack->rxbufstat)[idxf] == EC_BUF_TX)
|
||||
@ -573,7 +573,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
return rval;
|
||||
}
|
||||
@ -582,7 +582,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
* it skips the secondary stack and redundancy functions. In redundant mode it waits
|
||||
* for both (primary and secondary) frames to come in. The result goes in an decision
|
||||
* tree that decides, depending on the route of the packet and its possible missing arrival,
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
*
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] timer = absolute timeout time
|
||||
@ -595,27 +595,27 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
{
|
||||
wkc2 = 0;
|
||||
}
|
||||
do
|
||||
do
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
wkc = ecx_inframe(port, idx, 0);
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
{
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
@ -626,7 +626,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
||||
/* primary socket got secondary frame and secondary socket got primary frame */
|
||||
/* normal situation in redundant mode */
|
||||
if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
|
||||
@ -634,9 +634,9 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
|
||||
{
|
||||
@ -644,30 +644,30 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
|
||||
{
|
||||
{
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port,idx,1);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
{
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] idx = requested index of frame
|
||||
@ -679,7 +679,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
|
||||
if (timeout == 0 && (port->redstate == ECT_RED_NONE))
|
||||
{
|
||||
int loop_cnt = 0;
|
||||
@ -692,7 +692,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
}
|
||||
else
|
||||
{
|
||||
osal_timer_start (&timer, timeout);
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
}
|
||||
|
||||
@ -719,7 +719,7 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
/* tx frame on primary and if in redundant mode a dummy on secondary */
|
||||
ecx_outframe_red(port, idx);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer1);
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for nicdrv.c
|
||||
* Headerfile for nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
@ -69,7 +69,7 @@ typedef struct
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
} ec_stackT;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
@ -114,8 +114,8 @@ typedef struct
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
RTHANDLE getindex_region;
|
||||
ecx_redportt *redport;
|
||||
RTHANDLE getindex_region;
|
||||
RTHANDLE tx_region;
|
||||
RTHANDLE rx_region;
|
||||
/* Intime */
|
||||
|
@ -75,7 +75,7 @@ ec_adaptert * oshw_find_adapters (void)
|
||||
}
|
||||
|
||||
/** Free memory allocated memory used by adapter collection.
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
void oshw_free_adapters (ec_adaptert * adapter)
|
||||
|
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for oshw.c
|
||||
* Headerfile for oshw.c
|
||||
*/
|
||||
|
||||
#ifndef _oshw_
|
||||
|
@ -68,10 +68,10 @@
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <net/if.h>
|
||||
#include <sys/socket.h>
|
||||
#include <net/if.h>
|
||||
#include <sys/socket.h>
|
||||
#include <unistd.h>
|
||||
#include <sys/time.h>
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <stdio.h>
|
||||
@ -123,7 +123,7 @@ static void ecx_clear_rxbufstat(int *rxbufstat)
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
int i;
|
||||
int r, rval, ifindex;
|
||||
@ -174,12 +174,12 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
psock = &(port->sockhandle);
|
||||
}
|
||||
}
|
||||
/* we use RAW packet socket, with packet type ETH_P_ECAT */
|
||||
*psock = socket(PF_PACKET, SOCK_RAW, htons(ETH_P_ECAT));
|
||||
|
||||
|
||||
timeout.tv_sec = 0;
|
||||
timeout.tv_usec = 1;
|
||||
timeout.tv_usec = 1;
|
||||
r = setsockopt(*psock, SOL_SOCKET, SO_RCVTIMEO, &timeout, sizeof(timeout));
|
||||
r = setsockopt(*psock, SOL_SOCKET, SO_SNDTIMEO, &timeout, sizeof(timeout));
|
||||
i = 1;
|
||||
@ -201,14 +201,14 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
sll.sll_protocol = htons(ETH_P_ECAT);
|
||||
r = bind(*psock, (struct sockaddr *)&sll, sizeof(sll));
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
ec_setupheader(&(port->txbuf[i]));
|
||||
port->rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
ec_setupheader(&(port->txbuf2));
|
||||
if (r == 0) rval = 1;
|
||||
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -216,13 +216,13 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
* @param[in] port = port context struct
|
||||
* @return 0
|
||||
*/
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
if (port->sockhandle >= 0)
|
||||
if (port->sockhandle >= 0)
|
||||
close(port->sockhandle);
|
||||
if ((port->redport) && (port->redport->sockhandle >= 0))
|
||||
close(port->redport->sockhandle);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -231,7 +231,7 @@ int ecx_closenic(ecx_portt *port)
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
void ec_setupheader(void *p)
|
||||
{
|
||||
ec_etherheadert *bp;
|
||||
bp = p;
|
||||
@ -257,7 +257,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
|
||||
idx = port->lastidx + 1;
|
||||
/* index can't be larger than buffer array */
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
@ -267,7 +267,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
idx++;
|
||||
cnt++;
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
@ -278,7 +278,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
port->lastidx = idx;
|
||||
|
||||
pthread_mutex_unlock( &(port->getindex_mutex) );
|
||||
|
||||
|
||||
return idx;
|
||||
}
|
||||
|
||||
@ -316,7 +316,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
rval = send(*stack->sock, (*stack->txbuf)[idx], lp, 0);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -337,7 +337,7 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
pthread_mutex_lock( &(port->tx_mutex) );
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
@ -350,8 +350,8 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
send(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2 , 0);
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -376,7 +376,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
lp = sizeof(port->tempinbuf);
|
||||
bytesrx = recv(*stack->sock, (*stack->tempbuf), lp, 0);
|
||||
port->tempinbufs = bytesrx;
|
||||
|
||||
|
||||
return (bytesrx > 0);
|
||||
}
|
||||
|
||||
@ -389,7 +389,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
* than requested index, store in buffer and exit. 3 frame read with matching
|
||||
* index, store in buffer, set completed flag in buffer status and exit.
|
||||
*
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
@ -417,7 +417,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
{
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
@ -425,22 +425,22 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
pthread_mutex_lock(&(port->rx_mutex));
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
{
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp =(ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == htons(ETH_P_ECAT))
|
||||
if (ehp->etype == htons(ETH_P_ECAT))
|
||||
{
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
if (idxf == idx)
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
@ -451,10 +451,10 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* check if index exist? */
|
||||
if (idxf < EC_MAXBUF)
|
||||
if (idxf < EC_MAXBUF)
|
||||
{
|
||||
rxbuf = &(*stack->rxbuf)[idxf];
|
||||
/* put it in the buffer array (strip ethernet header) */
|
||||
@ -463,7 +463,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
|
||||
(*stack->rxsa)[idxf] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
}
|
||||
@ -471,9 +471,9 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
}
|
||||
}
|
||||
pthread_mutex_unlock( &(port->rx_mutex) );
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
return rval;
|
||||
}
|
||||
@ -482,7 +482,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
* it skips the secondary stack and redundancy functions. In redundant mode it waits
|
||||
* for both (primary and secondary) frames to come in. The result goes in an decision
|
||||
* tree that decides, depending on the route of the packet and its possible missing arrival,
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
@ -496,23 +496,23 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
wkc2 = 0;
|
||||
do
|
||||
do
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
wkc = ecx_inframe(port, idx, 0);
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
@ -523,7 +523,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
||||
/* primary socket got secondary frame and secondary socket got primary frame */
|
||||
/* normal situation in redundant mode */
|
||||
if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
|
||||
@ -531,9 +531,9 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
|
||||
{
|
||||
@ -541,30 +541,30 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
|
||||
{
|
||||
{
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port, idx, 1);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
{
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] port = port context struct
|
||||
@ -577,15 +577,15 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
@ -607,29 +607,29 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
osal_timert timer1, timer2;
|
||||
|
||||
osal_timer_start (&timer1, timeout);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* tx frame on primary and if in redundant mode a dummy on secondary */
|
||||
ecx_outframe_red(port, idx);
|
||||
if (timeout < EC_TIMEOUTRET)
|
||||
if (timeout < EC_TIMEOUTRET)
|
||||
{
|
||||
osal_timer_start (&timer2, timeout);
|
||||
osal_timer_start (&timer2, timeout);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for nicdrv.c
|
||||
* Headerfile for nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
@ -71,7 +71,7 @@ typedef struct
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
} ec_stackT;
|
||||
|
||||
/** pointer structure to buffers for redundant port */
|
||||
typedef struct
|
||||
@ -116,8 +116,8 @@ typedef struct
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
pthread_mutex_t getindex_mutex;
|
||||
ecx_redportt *redport;
|
||||
pthread_mutex_t getindex_mutex;
|
||||
pthread_mutex_t tx_mutex;
|
||||
pthread_mutex_t rx_mutex;
|
||||
} ecx_portt;
|
||||
|
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatbase.c
|
||||
* Headerfile for ethercatbase.c
|
||||
*/
|
||||
|
||||
#ifndef _oshw_
|
||||
|
@ -508,14 +508,14 @@ static void fec_ecat_init_hw (const fec_mac_address_t * mac_address)
|
||||
{
|
||||
;
|
||||
}
|
||||
|
||||
|
||||
// Configure MDC clock.
|
||||
mii_speed = (fec->clock + 499999) / 5000000;
|
||||
fec->base->mscr = (fec->base->mscr & (~0x7E)) | (mii_speed << 1);
|
||||
|
||||
// Receive control register
|
||||
fec->base->rcr = FEC_RCR_MAX_FL(PKT_MAXBUF_SIZE) | FEC_RCR_MII_MODE;
|
||||
|
||||
|
||||
// set RMII mode in RCR register.
|
||||
if (fec->phy_interface == FEC_PHY_RMII)
|
||||
{
|
||||
@ -538,11 +538,11 @@ static void fec_ecat_init_hw (const fec_mac_address_t * mac_address)
|
||||
*/
|
||||
fec->base->iaur = 0;
|
||||
fec->base->ialr = 0;
|
||||
|
||||
|
||||
/* Receive all multicast frames. */
|
||||
fec->base->gaur = UINT32_MAX;
|
||||
fec->base->galr = UINT32_MAX;
|
||||
|
||||
|
||||
/* Set our physical address. */
|
||||
fec->base->pa.lower = (mac_address->octet[0] << 24) +
|
||||
(mac_address->octet[1] << 16) +
|
||||
@ -551,7 +551,7 @@ static void fec_ecat_init_hw (const fec_mac_address_t * mac_address)
|
||||
fec->base->pa.upper = (mac_address->octet[4] << 24) +
|
||||
(mac_address->octet[5] << 16) +
|
||||
0x8808;
|
||||
|
||||
|
||||
/* Start link autonegotiation */
|
||||
fec->phy->ops->start (fec->phy);
|
||||
}
|
||||
@ -559,11 +559,11 @@ static void fec_ecat_init_hw (const fec_mac_address_t * mac_address)
|
||||
int fec_ecat_send (const void *payload, size_t tot_len)
|
||||
{
|
||||
fec_buffer_bd_t * bd;
|
||||
|
||||
|
||||
/* Frames larger than the maximum Ethernet frame size are not allowed. */
|
||||
ASSERT (tot_len <= PKT_MAXBUF_SIZE);
|
||||
ASSERT (tot_len <= TX_BUFFER_SIZE);
|
||||
|
||||
|
||||
/* Bus errors should never occur, unless the MPU is enabled and forbids
|
||||
* the Ethernet MAC DMA from accessing the descriptors or buffers.
|
||||
*/
|
||||
@ -577,7 +577,7 @@ int fec_ecat_send (const void *payload, size_t tot_len)
|
||||
{
|
||||
bd = fec_buffer_get_tx ();
|
||||
}
|
||||
|
||||
|
||||
DPRINT ("out (%u):\n", tot_len);
|
||||
DUMP_PACKET (payload, tot_len);
|
||||
|
||||
@ -608,7 +608,7 @@ int fec_ecat_recv (void * buffer, size_t buffer_length)
|
||||
fec_buffer_bd_t * bd;
|
||||
int return_value;
|
||||
size_t frame_length_without_fcs;
|
||||
|
||||
|
||||
/* Bus errors should never occur, unless the MPU is enabled and forbids
|
||||
* the Ethernet MAC DMA from accessing the descriptors or buffers.
|
||||
*/
|
||||
@ -669,11 +669,11 @@ static void fec_ecat_hotplug (void)
|
||||
|
||||
/* Disable frame reception/transmission */
|
||||
fec->base->ecr &= ~FEC_ECR_ETHER_EN;
|
||||
|
||||
|
||||
/* Set duplex mode according to link state */
|
||||
|
||||
link_state = fec->phy->ops->get_link_state (fec->phy);
|
||||
|
||||
|
||||
/* Set duplex */
|
||||
if (link_state & PHY_LINK_FULL_DUPLEX)
|
||||
{
|
||||
@ -695,7 +695,7 @@ static void fec_ecat_hotplug (void)
|
||||
{
|
||||
fec->base->rcr &= ~FEC_RCR_RMII_10T;
|
||||
}
|
||||
|
||||
|
||||
/* Clear any pending interrupt */
|
||||
fec->base->eir = 0xffffffff;
|
||||
|
||||
@ -713,10 +713,10 @@ static void fec_ecat_hotplug (void)
|
||||
|
||||
// FEC_ERDSR - Receive buffer descriptor ring start register
|
||||
fec->base->erdsr = (uint32_t)fec->rx_bd_base;
|
||||
|
||||
|
||||
// FEC_ETDSR - Transmit buffer descriptor ring start register
|
||||
fec->base->etdsr = (uint32_t)fec->tx_bd_base;
|
||||
|
||||
|
||||
// FEC_EMRBR - Maximum receive buffer size register
|
||||
fec->base->emrbr = RX_BUFFER_SIZE - 1;
|
||||
|
||||
@ -730,11 +730,11 @@ static void fec_ecat_hotplug (void)
|
||||
* MAC hardware. Software would otherwise need to do the conversions.
|
||||
*/
|
||||
fec->base->ecr = FEC_ECR_ETHER_EN | FEC_ECR_DBSWP;
|
||||
|
||||
|
||||
/* Indicate that there have been empty receive buffers produced */
|
||||
// FEC_RDAR - Receive Descriptor ring - Receive descriptor active register
|
||||
fec->base->rdar = 1;
|
||||
|
||||
|
||||
DPRINT ("Link up. Speed: %s. Mode: %s.\n", fec_ecat_link_speed_name (link_state),
|
||||
fec_ecat_link_duplex_name (link_state));
|
||||
}
|
||||
@ -742,9 +742,9 @@ static void fec_ecat_hotplug (void)
|
||||
static dev_state_t fec_ecat_probe (void)
|
||||
{
|
||||
uint8_t link_state;
|
||||
|
||||
|
||||
link_state = fec->phy->ops->get_link_state (fec->phy);
|
||||
|
||||
|
||||
return (link_state & PHY_LINK_OK) ? StateAttached : StateDetached;
|
||||
}
|
||||
|
||||
@ -777,7 +777,7 @@ int fec_ecat_init (const fec_mac_address_t * mac_address,
|
||||
|
||||
fec = malloc (sizeof (fec_t));
|
||||
UASSERT (fec != NULL, EMEM);
|
||||
|
||||
|
||||
/* Initialise driver state */
|
||||
fec->rx_bd_base = eth_cfg.rx_bd_base;
|
||||
fec->tx_bd_base = eth_cfg.tx_bd_base;
|
||||
|
@ -20,7 +20,7 @@
|
||||
|
||||
/**
|
||||
* \defgroup fec EtherCat Ethernet MAC driver for Frescale K60 SoCs.
|
||||
*
|
||||
*
|
||||
* \{
|
||||
*/
|
||||
|
||||
@ -52,5 +52,5 @@ int fec_ecat_recv (void * buffer, size_t buffer_length);
|
||||
#endif /* FEC_H */
|
||||
|
||||
/**
|
||||
* \}
|
||||
* \}
|
||||
*/
|
||||
|
@ -211,9 +211,9 @@ static uint8_t lw_emac_init_registers(uint8_t * ethAddr) {
|
||||
*(uint16_t *) PORTH_FER = 0xFFFF;
|
||||
|
||||
/* CONFIGURE MAC REGISTERS */
|
||||
|
||||
/*
|
||||
* Set the MMC (MAC Management Counter) control register
|
||||
|
||||
/*
|
||||
* Set the MMC (MAC Management Counter) control register
|
||||
* RTSC = Clear all counters
|
||||
*
|
||||
* Note that counters are not enabled at this time
|
||||
@ -233,10 +233,10 @@ static uint8_t lw_emac_init_registers(uint8_t * ethAddr) {
|
||||
);
|
||||
|
||||
/*
|
||||
* Set the system control register
|
||||
* Set the system control register
|
||||
* SET_MDCDIV(x) = Set MDC to 2.5 MHz
|
||||
* RXDWA = Pad incoming frame with 0x0000 as to make the data-part 32-bit aligned
|
||||
* RXCKS = Enable Receive Frame TCP/UDP Checksum Computation
|
||||
* RXDWA = Pad incoming frame with 0x0000 as to make the data-part 32-bit aligned
|
||||
* RXCKS = Enable Receive Frame TCP/UDP Checksum Computation
|
||||
*/
|
||||
pEth->sysctl = SET_MDCDIV(sysctl_mdcdiv) | RXDWA ;
|
||||
|
||||
@ -244,8 +244,8 @@ static uint8_t lw_emac_init_registers(uint8_t * ethAddr) {
|
||||
|
||||
/*
|
||||
* Set the PHY basic control register
|
||||
* MII_BMCR_ANEG_EN = Auto negotiation on
|
||||
* MII_BMCR_ANEG_RST = Restart the auto-neg process by setting
|
||||
* MII_BMCR_ANEG_EN = Auto negotiation on
|
||||
* MII_BMCR_ANEG_RST = Restart the auto-neg process by setting
|
||||
* Speed handled by auto negotiation
|
||||
*/
|
||||
phy_stadat = MII_BMCR_ANEG_EN | MII_BMCR_ANEG_RST;
|
||||
@ -273,7 +273,7 @@ static uint8_t lw_emac_init_registers(uint8_t * ethAddr) {
|
||||
}
|
||||
else {
|
||||
pEth->opmode = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Setup DMA MAC receive/transfer channels with XCOUNT 0 (which we use
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : nicdrv.c
|
||||
* Version : 1.3.1
|
||||
@ -121,7 +121,7 @@ static void ecx_clear_rxbufstat(int *rxbufstat)
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
int i;
|
||||
int rVal;
|
||||
@ -134,7 +134,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
rVal = bfin_EMAC_init((uint8_t *)priMAC);
|
||||
if (rVal != 0)
|
||||
return 0;
|
||||
|
||||
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port stuct available? */
|
||||
@ -176,7 +176,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
psock = &(port->sockhandle);
|
||||
}
|
||||
}
|
||||
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
@ -193,9 +193,9 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
* @param[in] port = port context struct
|
||||
* @return 0
|
||||
*/
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
if (port->sockhandle >= 0)
|
||||
if (port->sockhandle >= 0)
|
||||
{
|
||||
close(port->sockhandle);
|
||||
}
|
||||
@ -211,7 +211,7 @@ int ecx_closenic(ecx_portt *port)
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
void ec_setupheader(void *p)
|
||||
{
|
||||
ec_etherheadert *bp;
|
||||
bp = p;
|
||||
@ -237,7 +237,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
|
||||
idx = port->lastidx + 1;
|
||||
/* index can't be larger than buffer array */
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
@ -247,7 +247,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
idx++;
|
||||
cnt++;
|
||||
if (idx >= EC_MAXBUF)
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
@ -260,7 +260,7 @@ int ecx_getindex(ecx_portt *port)
|
||||
port->lastidx = idx;
|
||||
|
||||
mtx_unlock (port->getindex_mutex);
|
||||
|
||||
|
||||
return idx;
|
||||
}
|
||||
|
||||
@ -321,7 +321,7 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
mtx_lock (port->tx_mutex);
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
@ -337,8 +337,8 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
bfin_EMAC_send(&(port->txbuf2), port->txbuflength2);
|
||||
mtx_unlock (port->tx_mutex);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -376,7 +376,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
* than requested index, store in buffer and exit. 3 frame read with matching
|
||||
* index, store in buffer, set completed flag in buffer status and exit.
|
||||
*
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
@ -404,7 +404,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ( (*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
if ((idx < EC_MAXBUF) && ( (*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
{
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
@ -412,22 +412,22 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
mtx_lock (port->rx_mutex);
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
{
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp =(ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == oshw_htons(ETH_P_ECAT))
|
||||
{
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
if (idxf == idx)
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
@ -438,10 +438,10 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = oshw_ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* check if index exist? */
|
||||
if (idxf < EC_MAXBUF)
|
||||
if (idxf < EC_MAXBUF)
|
||||
{
|
||||
rxbuf = &(*stack->rxbuf)[idxf];
|
||||
/* put it in the buffer array (strip ethernet header) */
|
||||
@ -450,7 +450,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
|
||||
(*stack->rxsa)[idxf] = oshw_ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
}
|
||||
@ -458,9 +458,9 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
}
|
||||
}
|
||||
mtx_unlock (port->rx_mutex);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
return rval;
|
||||
}
|
||||
@ -469,7 +469,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
* it skips the secondary stack and redundancy functions. In redundant mode it waits
|
||||
* for both (primary and secondary) frames to come in. The result goes in an decision
|
||||
* tree that decides, depending on the route of the packet and its possible missing arrival,
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
@ -482,13 +482,13 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
{
|
||||
wkc2 = 0;
|
||||
}
|
||||
do
|
||||
do
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
@ -497,25 +497,25 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
||||
}
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && (osal_timer_is_expired(&timer) == FALSE));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME)
|
||||
{
|
||||
if (wkc > EC_NOFRAME)
|
||||
{
|
||||
primrx = port->rxsa[idx];
|
||||
}
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
secrx = port->redport->rxsa[idx];
|
||||
}
|
||||
@ -526,9 +526,9 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
|
||||
{
|
||||
@ -538,30 +538,30 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
|
||||
{
|
||||
{
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start(&read_timer, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port, idx, 1);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && (osal_timer_is_expired(&read_timer) == FALSE));
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
{
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] port = port context struct
|
||||
@ -574,15 +574,15 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
@ -604,7 +604,7 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start(&timer, timeout);
|
||||
do
|
||||
do
|
||||
{
|
||||
osal_timert read_timer;
|
||||
|
||||
@ -613,14 +613,14 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
osal_timer_start(&read_timer, MIN(timeout, EC_TIMEOUTRET));
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, read_timer);
|
||||
/* wait for answer with WKC>0 or otherwise retry until timeout */
|
||||
/* wait for answer with WKC>0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && (osal_timer_is_expired(&timer) == FALSE));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
@ -40,9 +40,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for nicdrv.c
|
||||
* Headerfile for nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
@ -65,7 +65,7 @@ typedef struct
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
} ec_stackT;
|
||||
|
||||
/** pointer structure to buffers for redundant port */
|
||||
typedef struct
|
||||
@ -110,7 +110,7 @@ typedef struct
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
ecx_redportt *redport;
|
||||
mtx_t * getindex_mutex;
|
||||
mtx_t * tx_mutex;
|
||||
mtx_t * rx_mutex;
|
||||
|
@ -39,7 +39,7 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for oshw.c
|
||||
*/
|
||||
|
@ -123,7 +123,7 @@ static void ecx_clear_rxbufstat(int *rxbufstat)
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
int i, rval;
|
||||
pcap_t **psock;
|
||||
@ -170,9 +170,9 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
psock = &(port->sockhandle);
|
||||
}
|
||||
}
|
||||
/* we use pcap socket to send RAW packets in windows user mode*/
|
||||
*psock = pcap_open(ifname, 65536, PCAP_OPENFLAG_PROMISCUOUS |
|
||||
*psock = pcap_open(ifname, 65536, PCAP_OPENFLAG_PROMISCUOUS |
|
||||
PCAP_OPENFLAG_MAX_RESPONSIVENESS |
|
||||
PCAP_OPENFLAG_NOCAPTURE_LOCAL, -1, NULL , errbuf);
|
||||
if (NULL == *psock)
|
||||
@ -180,7 +180,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
printf("interface %s could not open with pcap\n", ifname);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
ec_setupheader(&(port->txbuf[i]));
|
||||
@ -195,11 +195,11 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
* @param[in] port = port context struct
|
||||
* @return 0
|
||||
*/
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
timeEndPeriod(15);
|
||||
|
||||
if (port->sockhandle != NULL)
|
||||
if (port->sockhandle != NULL)
|
||||
{
|
||||
DeleteCriticalSection(&(port->getindex_mutex));
|
||||
DeleteCriticalSection(&(port->tx_mutex));
|
||||
@ -306,7 +306,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
rval = pcap_sendpacket(*stack->sock, (*stack->txbuf)[idx], lp);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -327,7 +327,7 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
EnterCriticalSection( &(port->tx_mutex) );
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
@ -340,8 +340,8 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
pcap_sendpacket(port->redport->sockhandle, (u_char const *)&(port->txbuf2), port->txbuflength2);
|
||||
LeaveCriticalSection( &(port->tx_mutex) );
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
@ -421,7 +421,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
{
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
@ -429,22 +429,22 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
EnterCriticalSection(&(port->rx_mutex));
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
{
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp =(ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == htons(ETH_P_ECAT))
|
||||
if (ehp->etype == htons(ETH_P_ECAT))
|
||||
{
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
if (idxf == idx)
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
@ -455,10 +455,10 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* check if index exist? */
|
||||
if (idxf < EC_MAXBUF)
|
||||
if (idxf < EC_MAXBUF)
|
||||
{
|
||||
rxbuf = &(*stack->rxbuf)[idxf];
|
||||
/* put it in the buffer array (strip ethernet header) */
|
||||
@ -467,7 +467,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
|
||||
(*stack->rxsa)[idxf] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
}
|
||||
@ -475,9 +475,9 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
}
|
||||
}
|
||||
LeaveCriticalSection( &(port->rx_mutex) );
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
return rval;
|
||||
}
|
||||
@ -500,23 +500,23 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
wkc2 = 0;
|
||||
do
|
||||
do
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
wkc = ecx_inframe(port, idx, 0);
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
@ -527,7 +527,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
||||
/* primary socket got secondary frame and secondary socket got primary frame */
|
||||
/* normal situation in redundant mode */
|
||||
if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
|
||||
@ -535,9 +535,9 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
|
||||
{
|
||||
@ -545,30 +545,30 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
|
||||
{
|
||||
{
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port, idx, 1);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
{
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] port = port context struct
|
||||
@ -581,15 +581,15 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ec_setbufstat(idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
@ -611,29 +611,29 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
osal_timert timer1, timer2;
|
||||
|
||||
osal_timer_start (&timer1, timeout);
|
||||
do
|
||||
do
|
||||
{
|
||||
/* tx frame on primary and if in redundant mode a dummy on secondary */
|
||||
ecx_outframe_red(port, idx);
|
||||
if (timeout < EC_TIMEOUTRET)
|
||||
if (timeout < EC_TIMEOUTRET)
|
||||
{
|
||||
osal_timer_start (&timer2, timeout);
|
||||
osal_timer_start (&timer2, timeout);
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ec_setbufstat(idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : nicdrv.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for nicdrv.c
|
||||
* Headerfile for nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
@ -74,7 +74,7 @@ typedef struct
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
} ec_stackT;
|
||||
|
||||
/** pointer structure to buffers for redundant port */
|
||||
typedef struct
|
||||
@ -119,7 +119,7 @@ typedef struct
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
ecx_redportt *redport;
|
||||
CRITICAL_SECTION getindex_mutex;
|
||||
CRITICAL_SECTION tx_mutex;
|
||||
CRITICAL_SECTION rx_mutex;
|
||||
|
@ -86,7 +86,7 @@ ec_adaptert * oshw_find_adapters (void)
|
||||
fprintf(stderr,"Error in pcap_findalldevs_ex: %s\n", errbuf);
|
||||
return (NULL);
|
||||
}
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
* decsription.
|
||||
*/
|
||||
for(d= alldevs; d != NULL; d= d->next)
|
||||
@ -115,10 +115,10 @@ ec_adaptert * oshw_find_adapters (void)
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->name, d->name,string_len);
|
||||
adapter->name[string_len] = '\0';
|
||||
adapter->name[string_len] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
{
|
||||
adapter->name[0] = '\0';
|
||||
}
|
||||
if (d->description)
|
||||
@ -129,23 +129,23 @@ ec_adaptert * oshw_find_adapters (void)
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->desc, d->description,string_len);
|
||||
adapter->desc[string_len] = '\0';
|
||||
adapter->desc[string_len] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
adapter->desc[0] = '\0';
|
||||
adapter->desc[0] = '\0';
|
||||
}
|
||||
prev_adapter = adapter;
|
||||
i++;
|
||||
}
|
||||
/* free all devices allocated */
|
||||
pcap_freealldevs(alldevs);
|
||||
pcap_freealldevs(alldevs);
|
||||
|
||||
return ret_adapter;
|
||||
}
|
||||
|
||||
/** Free memory allocated memory used by adapter collection.
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
void oshw_free_adapters (ec_adaptert * adapter)
|
||||
@ -153,7 +153,7 @@ void oshw_free_adapters (ec_adaptert * adapter)
|
||||
ec_adaptert * next_adapter;
|
||||
/* Iterate the linked list and free all elemnts holding
|
||||
* adapter information
|
||||
*/
|
||||
*/
|
||||
if(adapter)
|
||||
{
|
||||
next_adapter = adapter->next;
|
||||
|
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatbase.c
|
||||
* Headerfile for ethercatbase.c
|
||||
*/
|
||||
|
||||
#ifndef _oshw_
|
||||
|
@ -12,9 +12,9 @@
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of the Politecnico di Torino, CACE Technologies
|
||||
* nor the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* 3. Neither the name of the Politecnico di Torino, CACE Technologies
|
||||
* nor the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
@ -32,7 +32,7 @@
|
||||
*/
|
||||
|
||||
/** @ingroup packetapi
|
||||
* @{
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup packet32h Packet.dll definitions and data structures
|
||||
@ -70,7 +70,7 @@ typedef struct _AirpcapHandle *PAirpcapHandle;
|
||||
|
||||
/// Alignment macro. Defines the alignment size.
|
||||
#define Packet_ALIGNMENT sizeof(int)
|
||||
/// Alignment macro. Rounds up to the next even multiple of Packet_ALIGNMENT.
|
||||
/// Alignment macro. Rounds up to the next even multiple of Packet_ALIGNMENT.
|
||||
#define Packet_WORDALIGN(x) (((x)+(Packet_ALIGNMENT-1))&~(Packet_ALIGNMENT-1))
|
||||
|
||||
#define NdisMediumNull -1 ///< Custom linktype: NDIS doesn't provide an equivalent
|
||||
@ -103,9 +103,9 @@ typedef struct NetType
|
||||
/*!
|
||||
\brief A BPF pseudo-assembly program.
|
||||
|
||||
The program will be injected in the kernel by the PacketSetBPF() function and applied to every incoming packet.
|
||||
The program will be injected in the kernel by the PacketSetBPF() function and applied to every incoming packet.
|
||||
*/
|
||||
struct bpf_program
|
||||
struct bpf_program
|
||||
{
|
||||
UINT bf_len; ///< Indicates the number of instructions of the program, i.e. the number of struct bpf_insn that will follow.
|
||||
struct bpf_insn *bf_insns; ///< A pointer to the first instruction of the program.
|
||||
@ -116,7 +116,7 @@ struct bpf_program
|
||||
|
||||
bpf_insn contains a single instruction for the BPF register-machine. It is used to send a filter program to the driver.
|
||||
*/
|
||||
struct bpf_insn
|
||||
struct bpf_insn
|
||||
{
|
||||
USHORT code; ///< Instruction type and addressing mode.
|
||||
UCHAR jt; ///< Jump if true
|
||||
@ -129,13 +129,13 @@ struct bpf_insn
|
||||
|
||||
It is used by packet.dll to return statistics about a capture session.
|
||||
*/
|
||||
struct bpf_stat
|
||||
struct bpf_stat
|
||||
{
|
||||
UINT bs_recv; ///< Number of packets that the driver received from the network adapter
|
||||
///< from the beginning of the current capture. This value includes the packets
|
||||
UINT bs_recv; ///< Number of packets that the driver received from the network adapter
|
||||
///< from the beginning of the current capture. This value includes the packets
|
||||
///< lost by the driver.
|
||||
UINT bs_drop; ///< number of packets that the driver lost from the beginning of a capture.
|
||||
///< Basically, a packet is lost when the the buffer of the driver is full.
|
||||
UINT bs_drop; ///< number of packets that the driver lost from the beginning of a capture.
|
||||
///< Basically, a packet is lost when the the buffer of the driver is full.
|
||||
///< In this situation the packet cannot be stored and the driver rejects it.
|
||||
UINT ps_ifdrop; ///< drops by interface. XXX not yet supported
|
||||
UINT bs_capt; ///< number of packets that pass the filter, find place in the kernel buffer and
|
||||
@ -147,9 +147,9 @@ struct bpf_stat
|
||||
|
||||
This structure defines the header associated with every packet delivered to the application.
|
||||
*/
|
||||
struct bpf_hdr
|
||||
struct bpf_hdr
|
||||
{
|
||||
struct timeval bh_tstamp; ///< The timestamp associated with the captured packet.
|
||||
struct timeval bh_tstamp; ///< The timestamp associated with the captured packet.
|
||||
///< It is stored in a TimeVal structure.
|
||||
UINT bh_caplen; ///< Length of captured portion. The captured portion <b>can be different</b>
|
||||
///< from the original packet, because it is possible (with a proper filter)
|
||||
@ -157,7 +157,7 @@ struct bpf_hdr
|
||||
UINT bh_datalen; ///< Original length of packet
|
||||
USHORT bh_hdrlen; ///< Length of bpf header (this struct plus alignment padding). In some cases,
|
||||
///< a padding could be added between the end of this structure and the packet
|
||||
///< data for performance reasons. This filed can be used to retrieve the actual data
|
||||
///< data for performance reasons. This filed can be used to retrieve the actual data
|
||||
///< of the packet.
|
||||
};
|
||||
|
||||
@ -170,9 +170,9 @@ struct bpf_hdr
|
||||
*/
|
||||
struct dump_bpf_hdr{
|
||||
struct timeval ts; ///< Time stamp of the packet
|
||||
UINT caplen; ///< Length of captured portion. The captured portion can smaller than the
|
||||
///< the original packet, because it is possible (with a proper filter) to
|
||||
///< instruct the driver to capture only a portion of the packets.
|
||||
UINT caplen; ///< Length of captured portion. The captured portion can smaller than the
|
||||
///< the original packet, because it is possible (with a proper filter) to
|
||||
///< instruct the driver to capture only a portion of the packets.
|
||||
UINT len; ///< Length of the original packet (off wire).
|
||||
};
|
||||
|
||||
@ -188,7 +188,7 @@ struct bpf_stat;
|
||||
/*!
|
||||
\brief Addresses of a network adapter.
|
||||
|
||||
This structure is used by the PacketGetNetInfoEx() function to return the IP addresses associated with
|
||||
This structure is used by the PacketGetNetInfoEx() function to return the IP addresses associated with
|
||||
an adapter.
|
||||
*/
|
||||
typedef struct npf_if_addr {
|
||||
@ -221,20 +221,20 @@ typedef WAN_ADAPTER *PWAN_ADAPTER; ///< Describes an opened wan (dialup, VPN...)
|
||||
This structure is the most important for the functioning of packet.dll, but the great part of its fields
|
||||
should be ignored by the user, since the library offers functions that avoid to cope with low-level parameters
|
||||
*/
|
||||
typedef struct _ADAPTER {
|
||||
typedef struct _ADAPTER {
|
||||
HANDLE hFile; ///< \internal Handle to an open instance of the NPF driver.
|
||||
CHAR SymbolicLink[MAX_LINK_NAME_LENGTH]; ///< \internal A string containing the name of the network adapter currently opened.
|
||||
int NumWrites; ///< \internal Number of times a packets written on this adapter will be repeated
|
||||
int NumWrites; ///< \internal Number of times a packets written on this adapter will be repeated
|
||||
///< on the wire.
|
||||
HANDLE ReadEvent; ///< A notification event associated with the read calls on the adapter.
|
||||
///< It can be passed to standard Win32 functions (like WaitForSingleObject
|
||||
///< or WaitForMultipleObjects) to wait until the driver's buffer contains some
|
||||
///< data. It is particularly useful in GUI applications that need to wait
|
||||
///< or WaitForMultipleObjects) to wait until the driver's buffer contains some
|
||||
///< data. It is particularly useful in GUI applications that need to wait
|
||||
///< concurrently on several events. In Windows NT/2000 the PacketSetMinToCopy()
|
||||
///< function can be used to define the minimum amount of data in the kernel buffer
|
||||
///< that will cause the event to be signalled.
|
||||
|
||||
UINT ReadTimeOut; ///< \internal The amount of time after which a read on the driver will be released and
|
||||
///< that will cause the event to be signalled.
|
||||
|
||||
UINT ReadTimeOut; ///< \internal The amount of time after which a read on the driver will be released and
|
||||
///< ReadEvent will be signaled, also if no packets were captured
|
||||
CHAR Name[ADAPTER_NAME_LENGTH];
|
||||
PWAN_ADAPTER pWanAdapter;
|
||||
@ -262,7 +262,7 @@ typedef struct _ADAPTER {
|
||||
|
||||
This structure defines the header associated with every packet delivered to the application.
|
||||
*/
|
||||
typedef struct _PACKET {
|
||||
typedef struct _PACKET {
|
||||
HANDLE hEvent; ///< \deprecated Still present for compatibility with old applications.
|
||||
OVERLAPPED OverLapped; ///< \deprecated Still present for compatibility with old applications.
|
||||
PVOID Buffer; ///< Buffer with containing the packets. See the PacketReceivePacket() for
|
||||
@ -276,17 +276,17 @@ typedef struct _PACKET {
|
||||
/*!
|
||||
\brief Structure containing an OID request.
|
||||
|
||||
It is used by the PacketRequest() function to send an OID to the interface card driver.
|
||||
It can be used, for example, to retrieve the status of the error counters on the adapter, its MAC address,
|
||||
It is used by the PacketRequest() function to send an OID to the interface card driver.
|
||||
It can be used, for example, to retrieve the status of the error counters on the adapter, its MAC address,
|
||||
the list of the multicast groups defined on it, and so on.
|
||||
*/
|
||||
struct _PACKET_OID_DATA {
|
||||
ULONG Oid; ///< OID code. See the Microsoft DDK documentation or the file ntddndis.h
|
||||
///< for a complete list of valid codes.
|
||||
ULONG Length; ///< Length of the data field
|
||||
UCHAR Data[1]; ///< variable-lenght field that contains the information passed to or received
|
||||
UCHAR Data[1]; ///< variable-lenght field that contains the information passed to or received
|
||||
///< from the adapter.
|
||||
};
|
||||
};
|
||||
typedef struct _PACKET_OID_DATA PACKET_OID_DATA, *PPACKET_OID_DATA;
|
||||
|
||||
#ifdef __cplusplus
|
||||
@ -308,7 +308,7 @@ BOOLEAN QueryWinPcapRegistryStringW(WCHAR *SubKeyName,
|
||||
UINT *pValueLen,
|
||||
WCHAR *DefaultVal);
|
||||
*/
|
||||
|
||||
|
||||
//---------------------------------------------------------------------------
|
||||
// EXPORTED FUNCTIONS
|
||||
//---------------------------------------------------------------------------
|
||||
@ -354,6 +354,6 @@ PAirpcapHandle PacketGetAirPcapHandle(LPADAPTER AdapterObject);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif //__PACKET32
|
||||
|
@ -12,9 +12,9 @@
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of the Politecnico di Torino, CACE Technologies
|
||||
* nor the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* 3. Neither the name of the Politecnico di Torino, CACE Technologies
|
||||
* nor the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
@ -67,7 +67,7 @@ typedef struct _AirpcapHandle *PAirpcapHandle;
|
||||
#define BPF_MEM_EX 0xc0
|
||||
#define BPF_TME 0x08
|
||||
|
||||
#define BPF_LOOKUP 0x90
|
||||
#define BPF_LOOKUP 0x90
|
||||
#define BPF_EXECUTE 0xa0
|
||||
#define BPF_INIT 0xb0
|
||||
#define BPF_VALIDATE 0xc0
|
||||
|
@ -1,7 +1,7 @@
|
||||
/*
|
||||
* Copyright (C) 1999 WIDE Project.
|
||||
* All rights reserved.
|
||||
*
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
@ -13,7 +13,7 @@
|
||||
* 3. Neither the name of the project nor the names of its contributors
|
||||
* may be used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE PROJECT AND CONTRIBUTORS ``AS IS'' AND
|
||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
@ -45,7 +45,7 @@ typedef signed int int8_t;
|
||||
|
||||
#endif /* HAVE_U_INT8_T */
|
||||
|
||||
#ifndef HAVE_U_INT16_T
|
||||
#ifndef HAVE_U_INT16_T
|
||||
|
||||
#if SIZEOF_SHORT == 2
|
||||
typedef unsigned short u_int16_t;
|
||||
|
@ -4,7 +4,7 @@
|
||||
*
|
||||
* This code is derived from the Stanford/CMU enet packet filter,
|
||||
* (net/enet.c) distributed as part of 4.3BSD, and code contributed
|
||||
* to Berkeley by Steven McCanne and Van Jacobson both of Lawrence
|
||||
* to Berkeley by Steven McCanne and Van Jacobson both of Lawrence
|
||||
* Berkeley Laboratory.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -39,7 +39,7 @@
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Avoids a compiler warning in case this was already defined
|
||||
* Avoids a compiler warning in case this was already defined
|
||||
* (someone defined _WINSOCKAPI_ when including 'windows.h', in order
|
||||
* to prevent it from including 'winsock.h')
|
||||
*/
|
||||
@ -66,7 +66,7 @@
|
||||
#define strdup _strdup
|
||||
#endif
|
||||
|
||||
#define inline __inline
|
||||
#define inline __inline
|
||||
|
||||
#ifdef __MINGW32__
|
||||
#include <stdint.h>
|
||||
@ -88,6 +88,6 @@ typedef __int64 intptr_t;
|
||||
typedef _W64 int intptr_t;
|
||||
#endif
|
||||
#define _INTPTR_T_DEFINED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif /*__MINGW32__*/
|
||||
|
@ -11,8 +11,8 @@
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. The name of the author may not be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* 3. The name of the author may not be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
@ -32,7 +32,7 @@
|
||||
*
|
||||
* @(#) $Header: /tcpdump/master/libpcap/pcap/bluetooth.h,v 1.1 2007/09/22 02:10:17 guy Exp $
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _PCAP_BLUETOOTH_STRUCTS_H__
|
||||
#define _PCAP_BLUETOOTH_STRUCTS_H__
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
*
|
||||
* This code is derived from the Stanford/CMU enet packet filter,
|
||||
* (net/enet.c) distributed as part of 4.3BSD, and code contributed
|
||||
* to Berkeley by Steven McCanne and Van Jacobson both of Lawrence
|
||||
* to Berkeley by Steven McCanne and Van Jacobson both of Lawrence
|
||||
* Berkeley Laboratory.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
@ -69,8 +69,8 @@ typedef u_int bpf_u_int32;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Alignment macros. BPF_WORDALIGN rounds up to the next
|
||||
* even multiple of BPF_ALIGNMENT.
|
||||
* Alignment macros. BPF_WORDALIGN rounds up to the next
|
||||
* even multiple of BPF_ALIGNMENT.
|
||||
*/
|
||||
#ifndef __NetBSD__
|
||||
#define BPF_ALIGNMENT sizeof(bpf_int32)
|
||||
@ -89,9 +89,9 @@ struct bpf_program {
|
||||
u_int bf_len;
|
||||
struct bpf_insn *bf_insns;
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* Struct return by BIOCVERSION. This represents the version number of
|
||||
* Struct return by BIOCVERSION. This represents the version number of
|
||||
* the filter language described by the instruction encodings below.
|
||||
* bpf understands a program iff kernel_major == filter_major &&
|
||||
* kernel_minor >= filter_minor, that is, if the value returned by the
|
||||
@ -353,7 +353,7 @@ struct bpf_version {
|
||||
*/
|
||||
#define DLT_SUNATM 123 /* Solaris+SunATM */
|
||||
|
||||
/*
|
||||
/*
|
||||
* Reserved as per request from Kent Dahlgren <kent@praesum.com>
|
||||
* for private use.
|
||||
*/
|
||||
@ -596,7 +596,7 @@ struct bpf_version {
|
||||
|
||||
/*
|
||||
* Juniper-private data link type, as per request from
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* The DLT_ are used for prepending meta-information
|
||||
* like interface index, interface name
|
||||
* before standard Ethernet, PPP, Frelay & C-HDLC Frames
|
||||
@ -613,7 +613,7 @@ struct bpf_version {
|
||||
|
||||
/*
|
||||
* Juniper-private data link type, as per request from
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* The DLT_ is used for internal communication with a
|
||||
* voice Adapter Card (PIC)
|
||||
*/
|
||||
@ -688,7 +688,7 @@ struct bpf_version {
|
||||
|
||||
/*
|
||||
* Juniper-private data link type, as per request from
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* The DLT_ is used for internal communication with a
|
||||
* integrated service module (ISM).
|
||||
*/
|
||||
@ -729,7 +729,7 @@ struct bpf_version {
|
||||
|
||||
/*
|
||||
* Juniper-private data link type, as per request from
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* Hannes Gredler <hannes@juniper.net>.
|
||||
* The DLT_ is used for capturing data on a secure tunnel interface.
|
||||
*/
|
||||
#define DLT_JUNIPER_ST 200
|
||||
|
@ -138,7 +138,7 @@ struct pcap_file_header {
|
||||
|
||||
/*
|
||||
* Macros for the value returned by pcap_datalink_ext().
|
||||
*
|
||||
*
|
||||
* If LT_FCS_LENGTH_PRESENT(x) is true, the LT_FCS_LENGTH(x) macro
|
||||
* gives the FCS length of packets in the capture.
|
||||
*/
|
||||
|
@ -11,8 +11,8 @@
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. The name of the author may not be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* 3. The name of the author may not be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
@ -32,11 +32,11 @@
|
||||
*
|
||||
* @(#) $Header: /tcpdump/master/libpcap/pcap/usb.h,v 1.6 2007/09/22 02:06:08 guy Exp $
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _PCAP_USB_STRUCTS_H__
|
||||
#define _PCAP_USB_STRUCTS_H__
|
||||
|
||||
/*
|
||||
/*
|
||||
* possible transfer mode
|
||||
*/
|
||||
#define URB_TRANSFER_IN 0x80
|
||||
|
@ -2,32 +2,32 @@
|
||||
* Copyright (c) 2002 - 2003
|
||||
* NetGroup, Politecnico di Torino (Italy)
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of the Politecnico di Torino nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from
|
||||
* this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
|
||||
* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
|
||||
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
|
||||
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
* 3. Neither the name of the Politecnico di Torino nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from
|
||||
* this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
|
||||
* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
|
||||
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
|
||||
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
@ -55,7 +55,7 @@ extern "C" {
|
||||
placed into the pcap.h file.
|
||||
|
||||
It includes all new definitions (structures and functions like pcap_open().
|
||||
Some of the functions are not really a remote feature, but, right now,
|
||||
Some of the functions are not really a remote feature, but, right now,
|
||||
they are placed here.
|
||||
*/
|
||||
|
||||
@ -85,25 +85,25 @@ extern "C" {
|
||||
|
||||
|
||||
/*!
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
remote/local interface).
|
||||
|
||||
This indicates a file, i.e. the user want to open a capture from a local file.
|
||||
*/
|
||||
#define PCAP_SRC_FILE 2
|
||||
/*!
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
remote/local interface).
|
||||
|
||||
This indicates a local interface, i.e. the user want to open a capture from
|
||||
This indicates a local interface, i.e. the user want to open a capture from
|
||||
a local interface. This does not involve the RPCAP protocol.
|
||||
*/
|
||||
#define PCAP_SRC_IFLOCAL 3
|
||||
/*!
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
\brief Internal representation of the type of source in use (file,
|
||||
remote/local interface).
|
||||
|
||||
This indicates a remote interface, i.e. the user want to open a capture from
|
||||
This indicates a remote interface, i.e. the user want to open a capture from
|
||||
an interface on a remote host. This does involve the RPCAP protocol.
|
||||
*/
|
||||
#define PCAP_SRC_IFREMOTE 4
|
||||
@ -147,7 +147,7 @@ extern "C" {
|
||||
- rpcap://[1:2:3::4]/devicename [IPv6 numeric, no port number]
|
||||
- rpcap://[1:2:3::4]:1234/devicename [IPv6 numeric, with port number]
|
||||
- rpcap://[1:2:3::4]:http/devicename [IPv6 numeric, with literal port number]
|
||||
|
||||
|
||||
\{
|
||||
*/
|
||||
|
||||
@ -194,7 +194,7 @@ extern "C" {
|
||||
|
||||
It is '1' if you have to open the adapter in promiscuous mode, '0' otherwise.
|
||||
Note that even if this parameter is false, the interface could well be in promiscuous
|
||||
mode for some other reason (for example because another capture process with
|
||||
mode for some other reason (for example because another capture process with
|
||||
promiscuous mode enabled is currently using that interface).
|
||||
On on Linux systems with 2.2 or later kernels (that have the "any" device), this
|
||||
flag does not work on the "any" device; if an argument of "any" is supplied,
|
||||
@ -209,7 +209,7 @@ extern "C" {
|
||||
If it is '1' if you want a UDP data connection, '0' if you want
|
||||
a TCP data connection; control connection is always TCP-based.
|
||||
A UDP connection is much lighter, but it does not guarantee that all
|
||||
the captured packets arrive to the client workstation. Moreover,
|
||||
the captured packets arrive to the client workstation. Moreover,
|
||||
it could be harmful in case of network congestion.
|
||||
This flag is meaningless if the source is not a remote interface.
|
||||
In that case, it is simply ignored.
|
||||
@ -230,7 +230,7 @@ extern "C" {
|
||||
/*!
|
||||
\brief Defines if the local adapter will capture its own generated traffic.
|
||||
|
||||
This flag tells the underlying capture driver to drop the packets that were sent by itself.
|
||||
This flag tells the underlying capture driver to drop the packets that were sent by itself.
|
||||
This is usefult when building applications like bridges, that should ignore the traffic
|
||||
they just sent.
|
||||
*/
|
||||
@ -239,11 +239,11 @@ extern "C" {
|
||||
/*!
|
||||
\brief This flag configures the adapter for maximum responsiveness.
|
||||
|
||||
In presence of a large value for nbytes, WinPcap waits for the arrival of several packets before
|
||||
copying the data to the user. This guarantees a low number of system calls, i.e. lower processor usage,
|
||||
i.e. better performance, which is good for applications like sniffers. If the user sets the
|
||||
PCAP_OPENFLAG_MAX_RESPONSIVENESS flag, the capture driver will copy the packets as soon as the application
|
||||
is ready to receive them. This is suggested for real time applications (like, for example, a bridge)
|
||||
In presence of a large value for nbytes, WinPcap waits for the arrival of several packets before
|
||||
copying the data to the user. This guarantees a low number of system calls, i.e. lower processor usage,
|
||||
i.e. better performance, which is good for applications like sniffers. If the user sets the
|
||||
PCAP_OPENFLAG_MAX_RESPONSIVENESS flag, the capture driver will copy the packets as soon as the application
|
||||
is ready to receive them. This is suggested for real time applications (like, for example, a bridge)
|
||||
that need the best responsiveness.*/
|
||||
#define PCAP_OPENFLAG_MAX_RESPONSIVENESS 16
|
||||
|
||||
@ -279,8 +279,8 @@ extern "C" {
|
||||
|
||||
In this case, the 'value' field of the 'pcap_samp' structure indicates the 'waiting
|
||||
time' in milliseconds before one packet got accepted.
|
||||
In other words, if 'value = 10', the first packet is returned to the caller; the next
|
||||
returned one will be the first packet that arrives when 10ms have elapsed.
|
||||
In other words, if 'value = 10', the first packet is returned to the caller; the next
|
||||
returned one will be the first packet that arrives when 10ms have elapsed.
|
||||
*/
|
||||
#define PCAP_SAMP_FIRST_AFTER_N_MS 2
|
||||
|
||||
@ -325,12 +325,12 @@ extern "C" {
|
||||
|
||||
\brief This structure keeps the information needed to autheticate
|
||||
the user on a remote machine.
|
||||
|
||||
The remote machine can either grant or refuse the access according
|
||||
|
||||
The remote machine can either grant or refuse the access according
|
||||
to the information provided.
|
||||
In case the NULL authentication is required, both 'username' and
|
||||
'password' can be NULL pointers.
|
||||
|
||||
|
||||
This structure is meaningless if the source is not a remote interface;
|
||||
in that case, the functions which requires such a structure can accept
|
||||
a NULL pointer as well.
|
||||
@ -341,24 +341,24 @@ struct pcap_rmtauth
|
||||
\brief Type of the authentication required.
|
||||
|
||||
In order to provide maximum flexibility, we can support different types
|
||||
of authentication based on the value of this 'type' variable. The currently
|
||||
of authentication based on the value of this 'type' variable. The currently
|
||||
supported authentication methods are defined into the
|
||||
\link remote_auth_methods Remote Authentication Methods Section\endlink.
|
||||
|
||||
*/
|
||||
int type;
|
||||
/*!
|
||||
\brief Zero-terminated string containing the username that has to be
|
||||
\brief Zero-terminated string containing the username that has to be
|
||||
used on the remote machine for authentication.
|
||||
|
||||
|
||||
This field is meaningless in case of the RPCAP_RMTAUTH_NULL authentication
|
||||
and it can be NULL.
|
||||
*/
|
||||
char *username;
|
||||
/*!
|
||||
\brief Zero-terminated string containing the password that has to be
|
||||
\brief Zero-terminated string containing the password that has to be
|
||||
used on the remote machine for authentication.
|
||||
|
||||
|
||||
This field is meaningless in case of the RPCAP_RMTAUTH_NULL authentication
|
||||
and it can be NULL.
|
||||
*/
|
||||
@ -427,7 +427,7 @@ struct pcap_samp *pcap_setsampling(pcap_t *p);
|
||||
|
||||
/** \name Remote Capture functions
|
||||
*/
|
||||
//\{
|
||||
//\{
|
||||
SOCKET pcap_remoteact_accept(const char *address, const char *port, const char *hostlist, char *connectinghost, struct pcap_rmtauth *auth, char *errbuf);
|
||||
int pcap_remoteact_list(char *hostlist, char sep, int size, char *errbuf);
|
||||
int pcap_remoteact_close(const char *host, char *errbuf);
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatbase.c
|
||||
* Version : 1.3.1
|
||||
@ -41,7 +41,7 @@
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Base EtherCAT functions.
|
||||
* Base EtherCAT functions.
|
||||
*
|
||||
* Setting up a datagram in an ethernet frame.
|
||||
* EtherCAT datagram primitives, broadcast, auto increment, configured and
|
||||
@ -112,10 +112,10 @@ int ecx_setupdatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, uint16
|
||||
datagramP = (ec_comt*)&frameP[ETH_HEADERSIZE];
|
||||
datagramP->elength = htoes(EC_ECATTYPE + EC_HEADERSIZE + length);
|
||||
datagramP->command = com;
|
||||
datagramP->index = idx;
|
||||
datagramP->index = idx;
|
||||
datagramP->ADP = htoes(ADP);
|
||||
datagramP->ADO = htoes(ADO);
|
||||
datagramP->dlength = htoes(length);
|
||||
datagramP->dlength = htoes(length);
|
||||
ecx_writedatagramdata(&frameP[ETH_HEADERSIZE + EC_HEADERSIZE], com, length, data);
|
||||
/* set WKC to zero */
|
||||
frameP[ETH_HEADERSIZE + EC_HEADERSIZE + length] = 0x00;
|
||||
@ -147,7 +147,7 @@ int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean
|
||||
|
||||
frameP = frame;
|
||||
/* copy previous frame size */
|
||||
prevlength = port->txbuflength[idx];
|
||||
prevlength = port->txbuflength[idx];
|
||||
datagramP = (ec_comt*)&frameP[ETH_HEADERSIZE];
|
||||
/* add new datagram to ethernet frame size */
|
||||
datagramP->elength = htoes( etohs(datagramP->elength) + EC_HEADERSIZE + length );
|
||||
@ -156,18 +156,18 @@ int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean
|
||||
/* set new EtherCAT header position */
|
||||
datagramP = (ec_comt*)&frameP[prevlength - EC_ELENGTHSIZE];
|
||||
datagramP->command = com;
|
||||
datagramP->index = idx;
|
||||
datagramP->index = idx;
|
||||
datagramP->ADP = htoes(ADP);
|
||||
datagramP->ADO = htoes(ADO);
|
||||
if (more)
|
||||
{
|
||||
/* this is not the last datagram to add */
|
||||
datagramP->dlength = htoes(length | EC_DATAGRAMFOLLOWS);
|
||||
datagramP->dlength = htoes(length | EC_DATAGRAMFOLLOWS);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* this is the last datagram in the frame */
|
||||
datagramP->dlength = htoes(length);
|
||||
datagramP->dlength = htoes(length);
|
||||
}
|
||||
ecx_writedatagramdata(&frameP[prevlength + EC_HEADERSIZE - EC_ELENGTHSIZE], com, length, data);
|
||||
/* set WKC to zero */
|
||||
@ -178,7 +178,7 @@ int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean
|
||||
|
||||
/* return offset to data in rx frame
|
||||
14 bytes smaller than tx frame due to stripping of ethernet header */
|
||||
return prevlength + EC_HEADERSIZE - EC_ELENGTHSIZE - ETH_HEADERSIZE;
|
||||
return prevlength + EC_HEADERSIZE - EC_ELENGTHSIZE - ETH_HEADERSIZE;
|
||||
}
|
||||
|
||||
/** BRW "broadcast write" primitive. Blocking.
|
||||
@ -190,7 +190,7 @@ int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean
|
||||
* @param[in] data = databuffer to be written to slaves
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_BWR (ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -206,7 +206,7 @@ int ecx_BWR (ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
ecx_setbufstat (port, idx, EC_BUF_EMPTY);
|
||||
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** BRD "broadcast read" primitive. Blocking.
|
||||
*
|
||||
@ -217,7 +217,7 @@ int ecx_BWR (ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_BRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -233,12 +233,12 @@ int ecx_BRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
{
|
||||
/* copy datagram to data buffer */
|
||||
memcpy(data, &(port->rxbuf[idx][EC_HEADERSIZE]), length);
|
||||
}
|
||||
}
|
||||
/* clear buffer status */
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** APRD "auto increment address read" primitive. Blocking.
|
||||
*
|
||||
@ -249,7 +249,7 @@ int ecx_BRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_APRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
@ -277,7 +277,7 @@ int ecx_APRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_ARMW(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
@ -305,7 +305,7 @@ int ecx_ARMW(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_FRMW(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
@ -330,7 +330,7 @@ int ecx_FRMW(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[in] ADO = Address Offset, slave memory address
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return word data from slave
|
||||
*/
|
||||
*/
|
||||
uint16 ecx_APRDw(ecx_portt *port, uint16 ADP, uint16 ADO, int timeout)
|
||||
{
|
||||
uint16 w;
|
||||
@ -350,7 +350,7 @@ uint16 ecx_APRDw(ecx_portt *port, uint16 ADP, uint16 ADO, int timeout)
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_FPRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
@ -375,7 +375,7 @@ int ecx_FPRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[in] ADO = Address Offset, slave memory address
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return word data from slave
|
||||
*/
|
||||
*/
|
||||
uint16 ecx_FPRDw(ecx_portt *port, uint16 ADP, uint16 ADO, int timeout)
|
||||
{
|
||||
uint16 w;
|
||||
@ -394,7 +394,7 @@ uint16 ecx_FPRDw(ecx_portt *port, uint16 ADP, uint16 ADO, int timeout)
|
||||
* @param[in] data = databuffer to write to slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_APWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -404,7 +404,7 @@ int ecx_APWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
ecx_setupdatagram(port, &(port->txbuf[idx]), EC_CMD_APWR, idx, ADP, ADO, length, data);
|
||||
wkc = ecx_srconfirm(port, idx, timeout);
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
@ -416,7 +416,7 @@ int ecx_APWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[in] data = word data to write to slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_APWRw(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 data, int timeout)
|
||||
{
|
||||
return ecx_APWR(port, ADP, ADO, sizeof(data), &data, timeout);
|
||||
@ -431,7 +431,7 @@ int ecx_APWRw(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 data, int timeout)
|
||||
* @param[in] data = databuffer to write to slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
@ -453,7 +453,7 @@ int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
||||
* @param[in] data = word to write to slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_FPWRw(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 data, int timeout)
|
||||
{
|
||||
return ecx_FPWR(port, ADP, ADO, sizeof(data), &data, timeout);
|
||||
@ -467,7 +467,7 @@ int ecx_FPWRw(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 data, int timeout)
|
||||
* @param[in,out] data = databuffer to write to and read from slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_LRW(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -493,7 +493,7 @@ int ecx_LRW(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeo
|
||||
* @param[out] data = databuffer to read from slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_LRD(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -519,7 +519,7 @@ int ecx_LRD(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeo
|
||||
* @param[in] data = databuffer to write to slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_LWR(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeout)
|
||||
{
|
||||
uint8 idx;
|
||||
@ -544,7 +544,7 @@ int ecx_LWR(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, int timeo
|
||||
* @param[out] DCtime = DC time read from reference slave.
|
||||
* @param[in] timeout = timeout in us, standard is EC_TIMEOUTRET
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
*/
|
||||
int ecx_LRWDC(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, uint16 DCrs, int64 *DCtime, int timeout)
|
||||
{
|
||||
uint16 DCtO;
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatbase.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatbase.c
|
||||
* Headerfile for ethercatbase.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatbase_
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatcoe.c
|
||||
* Version : 1.3.1
|
||||
@ -39,7 +39,7 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* CAN over EtherCAT (CoE) module.
|
||||
*
|
||||
@ -75,7 +75,7 @@ PACKED_END
|
||||
|
||||
/** SDO service structure */
|
||||
PACKED_BEGIN
|
||||
typedef struct PACKED
|
||||
typedef struct PACKED
|
||||
{
|
||||
ec_mbxheadert MbxHeader;
|
||||
uint16 CANOpen;
|
||||
@ -93,7 +93,7 @@ PACKED_END
|
||||
|
||||
/** Report SDO error.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Index = Index that generated error
|
||||
* @param[in] SubIdx = Subindex that generated error
|
||||
@ -116,7 +116,7 @@ void ecx_SDOerror(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubId
|
||||
|
||||
/** Report SDO info error
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Index = Index that generated error
|
||||
* @param[in] SubIdx = Subindex that generated error
|
||||
@ -137,13 +137,13 @@ static void ecx_SDOinfoerror(ecx_contextt *context, uint16 Slave, uint16 Index,
|
||||
}
|
||||
|
||||
/** CoE SDO read, blocking. Single subindex or Complete Access.
|
||||
*
|
||||
*
|
||||
* Only a "normal" upload request is issued. If the requested parameter is <= 4bytes
|
||||
* then a "expedited" response is returned, otherwise a "normal" response. If a "normal"
|
||||
* response is larger than the mailbox size then the response is segmented. The function
|
||||
* will combine all segments and copy them to the parameter buffer.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] index = Index to read
|
||||
* @param[in] subindex = Subindex to read, must be 0 or 1 if CA is used.
|
||||
@ -211,7 +211,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
||||
(aSDOp->Index == SDOp->Index))
|
||||
{
|
||||
if ((aSDOp->Command & 0x02) > 0)
|
||||
{
|
||||
{
|
||||
/* expedited frame response */
|
||||
bytesize = 4 - ((aSDOp->Command >> 2) & 0x03);
|
||||
if (*psize >= bytesize) /* parameter buffer big enough ? */
|
||||
@ -233,7 +233,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
||||
/* Does parameter fit in parameter buffer ? */
|
||||
if (SDOlen <= *psize)
|
||||
{
|
||||
bp = p;
|
||||
bp = p;
|
||||
hp = p;
|
||||
/* calculate mailbox transfer size */
|
||||
Framedatasize = (etohs(aSDOp->MbxHeader.length) - 10);
|
||||
@ -273,7 +273,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
||||
{
|
||||
/* slave response should be CoE, SDO response */
|
||||
if ((((aSDOp->MbxHeader.mbxtype & 0x0f) == ECT_MBXT_COE) &&
|
||||
((etohs(aSDOp->CANOpen) >> 12) == ECT_COES_SDORES) &&
|
||||
((etohs(aSDOp->CANOpen) >> 12) == ECT_COES_SDORES) &&
|
||||
((aSDOp->Command & 0xe0) == 0x00)))
|
||||
{
|
||||
/* calculate mailbox transfer size */
|
||||
@ -347,13 +347,13 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
||||
}
|
||||
|
||||
/** CoE SDO write, blocking. Single subindex or Complete Access.
|
||||
*
|
||||
*
|
||||
* A "normal" download request is issued, unless we have
|
||||
* small data, then a "expedited" transfer is used. If the parameter is larger than
|
||||
* the mailbox size then the download is segmented. The function will split the
|
||||
* parameter data in segments and send them to the slave one by one.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Index = Index to write
|
||||
* @param[in] SubIndex = Subindex to write, must be 0 or 1 if CA is used.
|
||||
@ -408,7 +408,7 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
||||
if (wkc > 0)
|
||||
{
|
||||
/* response should be CoE, SDO response, correct index and subindex */
|
||||
if (((aSDOp->MbxHeader.mbxtype & 0x0f) == ECT_MBXT_COE) &&
|
||||
if (((aSDOp->MbxHeader.mbxtype & 0x0f) == ECT_MBXT_COE) &&
|
||||
((etohs(aSDOp->CANOpen) >> 12) == ECT_COES_SDORES) &&
|
||||
(aSDOp->Index == SDOp->Index) &&
|
||||
(aSDOp->SubIndex == SDOp->SubIndex))
|
||||
@ -478,7 +478,7 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
||||
if (wkc > 0)
|
||||
{
|
||||
/* response should be CoE, SDO response, correct index and subindex */
|
||||
if (((aSDOp->MbxHeader.mbxtype & 0x0f) == ECT_MBXT_COE) &&
|
||||
if (((aSDOp->MbxHeader.mbxtype & 0x0f) == ECT_MBXT_COE) &&
|
||||
((etohs(aSDOp->CANOpen) >> 12) == ECT_COES_SDORES) &&
|
||||
(aSDOp->Index == SDOp->Index) &&
|
||||
(aSDOp->SubIndex == SDOp->SubIndex))
|
||||
@ -575,10 +575,10 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
||||
}
|
||||
|
||||
/** CoE RxPDO write, blocking.
|
||||
*
|
||||
*
|
||||
* A RxPDO download request is issued.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] RxPDOnumber = Related RxPDO number
|
||||
* @param[in] psize = Size in bytes of PDO buffer.
|
||||
@ -621,10 +621,10 @@ int ecx_RxPDO(ecx_contextt *context, uint16 Slave, uint16 RxPDOnumber, int psize
|
||||
}
|
||||
|
||||
/** CoE TxPDO read remote request, blocking.
|
||||
*
|
||||
*
|
||||
* A RxPDO download request is issued.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] TxPDOnumber = Related TxPDO number
|
||||
* @param[in,out] psize = Size in bytes of PDO buffer, returns bytes read from PDO.
|
||||
@ -682,7 +682,7 @@ int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psi
|
||||
wkc = 0;
|
||||
ecx_packeterror(context, slave, 0, 0, 3); /* data container too small for type */
|
||||
}
|
||||
}
|
||||
}
|
||||
/* other slave response */
|
||||
else
|
||||
{
|
||||
@ -696,14 +696,14 @@ int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psi
|
||||
}
|
||||
wkc = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Read PDO assign structure
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
@ -756,7 +756,7 @@ int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
rdl = sizeof(rdat); rdat = htoes(0xff);
|
||||
/* read Object Entry in Object database */
|
||||
// wkc = ec_readOEsingle(idx, (uint8)SubCount, pODlist, pOElist);
|
||||
bsize += etohs(rdat);
|
||||
bsize += etohs(rdat);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -767,7 +767,7 @@ int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
}
|
||||
|
||||
/** Read PDO assign structure in Complete Access mode
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
@ -778,7 +778,7 @@ int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
int wkc, bsize = 0, rdl;
|
||||
|
||||
/* find maximum size of PDOassign buffer */
|
||||
rdl = sizeof(ec_PDOassignt);
|
||||
rdl = sizeof(ec_PDOassignt);
|
||||
context->PDOassign->n=0;
|
||||
/* read rxPDOassign in CA mode, all subindexes are read in one struct */
|
||||
wkc = ecx_SDOread(context, Slave, PDOassign, 0x00, TRUE, &rdl, context->PDOassign, EC_TIMEOUTRXM);
|
||||
@ -833,8 +833,8 @@ int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
* 1A00:00 is number of object defined for this PDO\n
|
||||
* 1A00:01 object mapping #1, f.e. 60100710 (SDO 6010 SI 07 bitlength 0x10)
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
@ -846,7 +846,7 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
uint8 nSM, iSM, tSM;
|
||||
int Tsize;
|
||||
uint8 SMt_bug_add;
|
||||
|
||||
|
||||
*Isize = 0;
|
||||
*Osize = 0;
|
||||
SMt_bug_add = 0;
|
||||
@ -869,30 +869,30 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
wkc = ecx_SDOread(context, Slave, ECT_SDO_SMCOMMTYPE, iSM + 1, FALSE, &rdl, &tSM, EC_TIMEOUTRXM);
|
||||
if (wkc > 0)
|
||||
{
|
||||
// start slave bug prevention code, remove if possible
|
||||
// start slave bug prevention code, remove if possible
|
||||
if((iSM == 2) && (tSM == 2)) // SM2 has type 2 == mailbox out, this is a bug in the slave!
|
||||
{
|
||||
{
|
||||
SMt_bug_add = 1; // try to correct, this works if the types are 0 1 2 3 and should be 1 2 3 4
|
||||
}
|
||||
if(tSM)
|
||||
{
|
||||
{
|
||||
tSM += SMt_bug_add; // only add if SMt > 0
|
||||
}
|
||||
if((iSM == 2) && (tSM == 0)) // SM2 has type 0, this is a bug in the slave!
|
||||
{
|
||||
{
|
||||
tSM = 3;
|
||||
}
|
||||
if((iSM == 3) && (tSM == 0)) // SM3 has type 0, this is a bug in the slave!
|
||||
{
|
||||
{
|
||||
tSM = 4;
|
||||
}
|
||||
// end slave bug prevention code
|
||||
// end slave bug prevention code
|
||||
|
||||
context->slavelist[Slave].SMtype[iSM] = tSM;
|
||||
/* check if SM is unused -> clear enable flag */
|
||||
if (tSM == 0)
|
||||
{
|
||||
context->slavelist[Slave].SM[iSM].SMflags =
|
||||
context->slavelist[Slave].SM[iSM].SMflags =
|
||||
htoel( etohl(context->slavelist[Slave].SM[iSM].SMflags) & EC_SMENABLEMASK);
|
||||
}
|
||||
if ((tSM == 3) || (tSM == 4))
|
||||
@ -904,7 +904,7 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
{
|
||||
context->slavelist[Slave].SM[iSM].SMlength = htoes((Tsize + 7) / 8);
|
||||
if (tSM == 3)
|
||||
{
|
||||
{
|
||||
/* we are doing outputs */
|
||||
*Osize += Tsize;
|
||||
}
|
||||
@ -912,10 +912,10 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
{
|
||||
/* we are doing inputs */
|
||||
*Isize += Tsize;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -924,7 +924,7 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
{
|
||||
retVal = 1;
|
||||
}
|
||||
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
@ -934,8 +934,8 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
* tries to read them and collect a full input and output mapping size
|
||||
* of designated slave. Slave has to support CA, otherwise use ec_readPDOmap().
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
@ -947,11 +947,11 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
||||
uint8 nSM, iSM, tSM;
|
||||
int Tsize;
|
||||
uint8 SMt_bug_add;
|
||||
|
||||
|
||||
*Isize = 0;
|
||||
*Osize = 0;
|
||||
SMt_bug_add = 0;
|
||||
rdl = sizeof(ec_SMcommtypet);
|
||||
rdl = sizeof(ec_SMcommtypet);
|
||||
context->SMcommtype->n = 0;
|
||||
/* read SyncManager Communication Type object count Complete Access*/
|
||||
wkc = ecx_SDOread(context, Slave, ECT_SDO_SMCOMMTYPE, 0x00, TRUE, &rdl, context->SMcommtype, EC_TIMEOUTRXM);
|
||||
@ -964,14 +964,14 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
||||
if (nSM > EC_MAXSM)
|
||||
{
|
||||
nSM = EC_MAXSM;
|
||||
ecx_packeterror(context, Slave, 0, 0, 10); /* #SM larger than EC_MAXSM */
|
||||
ecx_packeterror(context, Slave, 0, 0, 10); /* #SM larger than EC_MAXSM */
|
||||
}
|
||||
/* iterate for every SM type defined */
|
||||
for (iSM = 2 ; iSM <= nSM ; iSM++)
|
||||
{
|
||||
tSM = context->SMcommtype->SMtype[iSM];
|
||||
|
||||
// start slave bug prevention code, remove if possible
|
||||
// start slave bug prevention code, remove if possible
|
||||
if((iSM == 2) && (tSM == 2)) // SM2 has type 2 == mailbox out, this is a bug in the slave!
|
||||
{
|
||||
SMt_bug_add = 1; // try to correct, this works if the types are 0 1 2 3 and should be 1 2 3 4
|
||||
@ -981,7 +981,7 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
||||
tSM += SMt_bug_add; // only add if SMt > 0
|
||||
}
|
||||
// end slave bug prevention code
|
||||
|
||||
|
||||
context->slavelist[Slave].SMtype[iSM] = tSM;
|
||||
/* check if SM is unused -> clear enable flag */
|
||||
if (tSM == 0)
|
||||
@ -1007,8 +1007,8 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
||||
/* we are doing inputs */
|
||||
*Isize += Tsize;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -1020,10 +1020,10 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/** CoE read Object Description List.
|
||||
/** CoE read Object Description List.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number.
|
||||
* @param[out] pODlist = resulting Object Description list.
|
||||
* @return Workcounter of slave response.
|
||||
*/
|
||||
@ -1062,7 +1062,7 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
||||
/* mailbox placed in slave ? */
|
||||
if (wkc > 0)
|
||||
{
|
||||
x = 0;
|
||||
x = 0;
|
||||
sp = 0;
|
||||
First = TRUE;
|
||||
offset = 1; /* offset to skip info header in first frame, otherwise set to 0 */
|
||||
@ -1080,7 +1080,7 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
||||
((aSDOp->Opcode & 0x7f) == ECT_GET_ODLIST_RES))
|
||||
{
|
||||
if (First)
|
||||
{
|
||||
{
|
||||
/* extract number of indexes from mailbox data size */
|
||||
n = (etohs(aSDOp->MbxHeader.length) - (6 + 2)) / 2;
|
||||
}
|
||||
@ -1110,10 +1110,10 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
||||
sp += n;
|
||||
/* check if more fragments will follow */
|
||||
if (aSDOp->Fragments > 0)
|
||||
{
|
||||
{
|
||||
stop = FALSE;
|
||||
}
|
||||
First = FALSE;
|
||||
First = FALSE;
|
||||
offset = 0;
|
||||
}
|
||||
/* got unexpected response from slave */
|
||||
@ -1128,7 +1128,7 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
||||
{
|
||||
ecx_packeterror(context, Slave, 0, 0, 1); /* Unexpected frame returned */
|
||||
}
|
||||
wkc = 0;
|
||||
wkc = 0;
|
||||
x += 20;
|
||||
}
|
||||
}
|
||||
@ -1141,7 +1141,7 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
||||
|
||||
/** CoE read Object Description. Adds textual description to object indexes.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Item = Item number in ODlist.
|
||||
* @param[in,out] pODlist = referencing Object Description list.
|
||||
* @return Workcounter of slave response.
|
||||
@ -1218,14 +1218,14 @@ int ecx_readODdescription(ecx_contextt *context, uint16 Item, ec_ODlistt *pODlis
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** CoE read SDO service object entry, single subindex.
|
||||
* Used in ec_readOE().
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Item = Item in ODlist.
|
||||
* @param[in] SubI = Subindex of item in ODlist.
|
||||
* @param[in] pODlist = Object description list for reference.
|
||||
@ -1310,13 +1310,13 @@ int ecx_readOEsingle(ecx_contextt *context, uint16 Item, uint8 SubI, ec_ODlistt
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** CoE read SDO service object entry.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Item = Item in ODlist.
|
||||
* @param[in] pODlist = Object description list for reference.
|
||||
* @param[out] pOElist = resulting object entry structure.
|
||||
@ -1337,65 +1337,178 @@ int ecx_readOE(ecx_contextt *context, uint16 Item, ec_ODlistt *pODlist, ec_OElis
|
||||
/* read subindex of entry */
|
||||
wkc = ecx_readOEsingle(context, Item, (uint8)SubCount, pODlist, pOElist);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
#ifdef EC_VER1
|
||||
/** Report SDO error.
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Index = Index that generated error
|
||||
* @param[in] SubIdx = Subindex that generated error
|
||||
* @param[in] AbortCode = Abortcode, see EtherCAT documentation for list
|
||||
* @see ecx_SDOerror
|
||||
*/
|
||||
void ec_SDOerror(uint16 Slave, uint16 Index, uint8 SubIdx, int32 AbortCode)
|
||||
{
|
||||
ecx_SDOerror(&ecx_context, Slave, Index, SubIdx, AbortCode);
|
||||
}
|
||||
|
||||
/** CoE SDO read, blocking. Single subindex or Complete Access.
|
||||
*
|
||||
* Only a "normal" upload request is issued. If the requested parameter is <= 4bytes
|
||||
* then a "expedited" response is returned, otherwise a "normal" response. If a "normal"
|
||||
* response is larger than the mailbox size then the response is segmented. The function
|
||||
* will combine all segments and copy them to the parameter buffer.
|
||||
*
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] index = Index to read
|
||||
* @param[in] subindex = Subindex to read, must be 0 or 1 if CA is used.
|
||||
* @param[in] CA = FALSE = single subindex. TRUE = Complete Access, all subindexes read.
|
||||
* @param[in,out] psize = Size in bytes of parameter buffer, returns bytes read from SDO.
|
||||
* @param[out] p = Pointer to parameter buffer
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response
|
||||
* @see ecx_SDOread
|
||||
*/
|
||||
int ec_SDOread(uint16 slave, uint16 index, uint8 subindex,
|
||||
boolean CA, int *psize, void *p, int timeout)
|
||||
{
|
||||
return ecx_SDOread(&ecx_context, slave, index, subindex, CA, psize, p, timeout);
|
||||
}
|
||||
|
||||
/** CoE SDO write, blocking. Single subindex or Complete Access.
|
||||
*
|
||||
* A "normal" download request is issued, unless we have
|
||||
* small data, then a "expedited" transfer is used. If the parameter is larger than
|
||||
* the mailbox size then the download is segmented. The function will split the
|
||||
* parameter data in segments and send them to the slave one by one.
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Index = Index to write
|
||||
* @param[in] SubIndex = Subindex to write, must be 0 or 1 if CA is used.
|
||||
* @param[in] CA = FALSE = single subindex. TRUE = Complete Access, all subindexes written.
|
||||
* @param[in] psize = Size in bytes of parameter buffer.
|
||||
* @param[out] p = Pointer to parameter buffer
|
||||
* @param[in] Timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response
|
||||
* @see ecx_SDOwrite
|
||||
*/
|
||||
int ec_SDOwrite(uint16 Slave, uint16 Index, uint8 SubIndex,
|
||||
boolean CA, int psize, void *p, int Timeout)
|
||||
{
|
||||
return ecx_SDOwrite(&ecx_context, Slave, Index, SubIndex, CA, psize, p, Timeout);
|
||||
}
|
||||
|
||||
/** CoE RxPDO write, blocking.
|
||||
*
|
||||
* A RxPDO download request is issued.
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] RxPDOnumber = Related RxPDO number
|
||||
* @param[in] psize = Size in bytes of PDO buffer.
|
||||
* @param[out] p = Pointer to PDO buffer
|
||||
* @return Workcounter from last slave response
|
||||
* @see ecx_RxPDO
|
||||
*/
|
||||
int ec_RxPDO(uint16 Slave, uint16 RxPDOnumber, int psize, void *p)
|
||||
{
|
||||
return ecx_RxPDO(&ecx_context, Slave, RxPDOnumber, psize, p);
|
||||
}
|
||||
|
||||
/** CoE TxPDO read remote request, blocking.
|
||||
*
|
||||
* A RxPDO download request is issued.
|
||||
*
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] TxPDOnumber = Related TxPDO number
|
||||
* @param[in,out] psize = Size in bytes of PDO buffer, returns bytes read from PDO.
|
||||
* @param[out] p = Pointer to PDO buffer
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response
|
||||
* @see ecx_TxPDO
|
||||
*/
|
||||
int ec_TxPDO(uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout)
|
||||
{
|
||||
return ecx_TxPDO(&ecx_context, slave, TxPDOnumber, psize, p, timeout);
|
||||
}
|
||||
|
||||
/** Read PDO assign structure */
|
||||
/** Read PDO assign structure
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
*/
|
||||
int ec_readPDOassign(uint16 Slave, uint16 PDOassign)
|
||||
{
|
||||
return ecx_readPDOassign(&ecx_context, Slave, PDOassign);
|
||||
}
|
||||
|
||||
/** Read PDO assign structure in Complete Access mode */
|
||||
/** Read PDO assign structure in Complete Access mode
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
* @see ecx_readPDOmap
|
||||
*/
|
||||
int ec_readPDOassignCA(uint16 Slave, uint16 PDOassign)
|
||||
{
|
||||
return ecx_readPDOassignCA(&ecx_context, Slave, PDOassign);
|
||||
}
|
||||
|
||||
/** CoE read PDO mapping.
|
||||
*
|
||||
* CANopen has standard indexes defined for PDO mapping. This function
|
||||
* tries to read them and collect a full input and output mapping size
|
||||
* of designated slave.
|
||||
*
|
||||
* For details, see #ecx_readPDOmap
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
*/
|
||||
int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize)
|
||||
{
|
||||
return ecx_readPDOmap(&ecx_context, Slave, Osize, Isize);
|
||||
}
|
||||
|
||||
/** CoE read PDO mapping in Complete Access mode (CA).
|
||||
*
|
||||
* CANopen has standard indexes defined for PDO mapping. This function
|
||||
* tries to read them and collect a full input and output mapping size
|
||||
* of designated slave. Slave has to support CA, otherwise use ec_readPDOmap().
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
* @see ecx_readPDOmap ec_readPDOmapCA
|
||||
*/
|
||||
int ec_readPDOmapCA(uint16 Slave, int *Osize, int *Isize)
|
||||
{
|
||||
return ecx_readPDOmapCA(&ecx_context, Slave, Osize, Isize);
|
||||
}
|
||||
|
||||
/** CoE read Object Description List.
|
||||
*
|
||||
* @param[in] Slave = Slave number.
|
||||
* @param[out] pODlist = resulting Object Description list.
|
||||
* @return Workcounter of slave response.
|
||||
* @see ecx_readODlist
|
||||
*/
|
||||
int ec_readODlist(uint16 Slave, ec_ODlistt *pODlist)
|
||||
{
|
||||
return ecx_readODlist(&ecx_context, Slave, pODlist);
|
||||
}
|
||||
|
||||
/** CoE read Object Description. Adds textual description to object indexes.
|
||||
*
|
||||
* @param[in] Item = Item number in ODlist.
|
||||
* @param[in,out] pODlist = referencing Object Description list.
|
||||
* @return Workcounter of slave response.
|
||||
* @see ecx_readODdescription
|
||||
*/
|
||||
int ec_readODdescription(uint16 Item, ec_ODlistt *pODlist)
|
||||
{
|
||||
return ecx_readODdescription(&ecx_context, Item, pODlist);
|
||||
@ -1406,6 +1519,14 @@ int ec_readOEsingle(uint16 Item, uint8 SubI, ec_ODlistt *pODlist, ec_OElistt *pO
|
||||
return ecx_readOEsingle(&ecx_context, Item, SubI, pODlist, pOElist);
|
||||
}
|
||||
|
||||
/** CoE read SDO service object entry.
|
||||
*
|
||||
* @param[in] Item = Item in ODlist.
|
||||
* @param[in] pODlist = Object description list for reference.
|
||||
* @param[out] pOElist = resulting object entry structure.
|
||||
* @return Workcounter of slave response.
|
||||
* @see ecx_readOE
|
||||
*/
|
||||
int ec_readOE(uint16 Item, ec_ODlistt *pODlist, ec_OElistt *pOElist)
|
||||
{
|
||||
return ecx_readOE(&ecx_context, Item, pODlist, pOElist);
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatcoe.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatcoe.c
|
||||
* Headerfile for ethercatcoe.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatcoe_
|
||||
@ -59,7 +59,7 @@ extern "C"
|
||||
#define EC_MAXOELIST 256
|
||||
|
||||
/* Storage for object description list */
|
||||
typedef struct
|
||||
typedef struct
|
||||
{
|
||||
/** slave number */
|
||||
uint16 Slave;
|
||||
@ -78,7 +78,7 @@ typedef struct
|
||||
} ec_ODlistt;
|
||||
|
||||
/* storage for object list entry information */
|
||||
typedef struct
|
||||
typedef struct
|
||||
{
|
||||
/** number of entries in list */
|
||||
uint16 Entries;
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatconfig.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatconfig.c
|
||||
* Headerfile for ethercatconfig.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatconfig_
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatconfiglist.h
|
||||
* Version : 1.3.1
|
||||
@ -52,14 +52,14 @@
|
||||
#define _ethercatconfiglist_
|
||||
|
||||
/*
|
||||
explanation of dev:
|
||||
1: static device with no IO mapping ie EK1100
|
||||
2: input device no mailbox ie simple IO device
|
||||
3: output device no mailbox
|
||||
4: input device with mailbox configuration
|
||||
5: output device with mailbox configuration
|
||||
6: input/output device no mailbox
|
||||
7: input.output device with mailbox configuration
|
||||
explanation of dev:
|
||||
1: static device with no IO mapping ie EK1100
|
||||
2: input device no mailbox ie simple IO device
|
||||
3: output device no mailbox
|
||||
4: input device with mailbox configuration
|
||||
5: output device with mailbox configuration
|
||||
6: input/output device no mailbox
|
||||
7: input.output device with mailbox configuration
|
||||
*/
|
||||
#define EC_CONFIGEND 0xffffffff
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatdc.c
|
||||
* Version : 1.3.1
|
||||
@ -41,7 +41,7 @@
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Distributed Clock EtherCAT functions.
|
||||
* Distributed Clock EtherCAT functions.
|
||||
*
|
||||
*/
|
||||
#include "oshw.h"
|
||||
@ -129,7 +129,7 @@ void ecx_dcsync01(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclT
|
||||
int64 t, t1;
|
||||
int32 tc;
|
||||
uint32 TrueCyclTime;
|
||||
|
||||
|
||||
/* Sync1 can be used as a multiple of Sync0, use true cycle time */
|
||||
TrueCyclTime = ((CyclTime1 / CyclTime0) + 1) * CyclTime0;
|
||||
|
||||
@ -234,7 +234,7 @@ static uint8 ecx_prevport(ecx_contextt *context, uint16 slave, uint8 port)
|
||||
else if (aport & PORTM1)
|
||||
pport = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return pport;
|
||||
}
|
||||
|
||||
@ -334,25 +334,25 @@ boolean ecx_configdc(ecx_contextt *context)
|
||||
|
||||
/* make list of active ports and their time stamps */
|
||||
nlist = 0;
|
||||
if (context->slavelist[i].activeports & PORTM0)
|
||||
if (context->slavelist[i].activeports & PORTM0)
|
||||
{
|
||||
plist[nlist] = 0;
|
||||
tlist[nlist] = context->slavelist[i].DCrtA;
|
||||
nlist++;
|
||||
}
|
||||
if (context->slavelist[i].activeports & PORTM3)
|
||||
if (context->slavelist[i].activeports & PORTM3)
|
||||
{
|
||||
plist[nlist] = 3;
|
||||
tlist[nlist] = context->slavelist[i].DCrtD;
|
||||
nlist++;
|
||||
}
|
||||
if (context->slavelist[i].activeports & PORTM1)
|
||||
if (context->slavelist[i].activeports & PORTM1)
|
||||
{
|
||||
plist[nlist] = 1;
|
||||
tlist[nlist] = context->slavelist[i].DCrtB;
|
||||
nlist++;
|
||||
}
|
||||
if (context->slavelist[i].activeports & PORTM2)
|
||||
if (context->slavelist[i].activeports & PORTM2)
|
||||
{
|
||||
plist[nlist] = 2;
|
||||
tlist[nlist] = context->slavelist[i].DCrtC;
|
||||
@ -363,7 +363,7 @@ boolean ecx_configdc(ecx_contextt *context)
|
||||
if((nlist > 1) && (tlist[1] < tlist[entryport]))
|
||||
{
|
||||
entryport = 1;
|
||||
}
|
||||
}
|
||||
if((nlist > 2) && (tlist[2] < tlist[entryport]))
|
||||
{
|
||||
entryport = 2;
|
||||
@ -401,13 +401,13 @@ boolean ecx_configdc(ecx_contextt *context)
|
||||
/* note: order of ports is 0 - 3 - 1 -2 */
|
||||
/* non active ports are skipped */
|
||||
dt3 = ecx_porttime(context, parent, context->slavelist[i].parentport) -
|
||||
ecx_porttime(context, parent,
|
||||
ecx_porttime(context, parent,
|
||||
ecx_prevport(context, parent, context->slavelist[i].parentport));
|
||||
/* current slave has children */
|
||||
/* those childrens delays need to be substacted */
|
||||
if (context->slavelist[i].topology > 1)
|
||||
{
|
||||
dt1 = ecx_porttime(context, i,
|
||||
dt1 = ecx_porttime(context, i,
|
||||
ecx_prevport(context, i, context->slavelist[i].entryport)) -
|
||||
ecx_porttime(context, i, context->slavelist[i].entryport);
|
||||
}
|
||||
@ -417,7 +417,7 @@ boolean ecx_configdc(ecx_contextt *context)
|
||||
/* previous childs delays need to be added */
|
||||
if ((child - parent) > 1)
|
||||
{
|
||||
dt2 = ecx_porttime(context, parent,
|
||||
dt2 = ecx_porttime(context, parent,
|
||||
ecx_prevport(context, parent, context->slavelist[i].parentport)) -
|
||||
ecx_porttime(context, parent, context->slavelist[parent].entryport);
|
||||
}
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatdc.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatdc.c
|
||||
* Headerfile for ethercatdc.c
|
||||
*/
|
||||
|
||||
#ifndef _EC_ECATDC_H
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatfoe.c
|
||||
* Version : 1.3.1
|
||||
@ -37,11 +37,11 @@
|
||||
* In case you did not receive a copy of the EtherCAT Master License along with
|
||||
* SOEM write to Beckhoff Automation GmbH, Eiserstraße 5, D-33415 Verl, Germany
|
||||
* (www.beckhoff.com).
|
||||
|
||||
|
||||
* 14-06-2010 : fixed bug in FOEread() by Torsten Bitterlich
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* File over EtherCAT (FoE) module.
|
||||
*
|
||||
@ -69,34 +69,34 @@ typedef struct PACKED
|
||||
uint8 OpCode;
|
||||
uint8 Reserved;
|
||||
union
|
||||
{
|
||||
{
|
||||
uint32 Password;
|
||||
uint32 PacketNumber;
|
||||
uint32 ErrorCode;
|
||||
};
|
||||
union
|
||||
{
|
||||
{
|
||||
char FileName[EC_MAXFOEDATA];
|
||||
uint8 Data[EC_MAXFOEDATA];
|
||||
char ErrorText[EC_MAXFOEDATA];
|
||||
};
|
||||
};
|
||||
} ec_FOEt;
|
||||
PACKED_END
|
||||
|
||||
/** FoE progress hook.
|
||||
*
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] hook = Pointer to hook function.
|
||||
* @return 1
|
||||
*/
|
||||
int ecx_FOEdefinehook(ecx_contextt *context, void *hook)
|
||||
{
|
||||
context->FOEhook = hook;
|
||||
context->FOEhook = hook;
|
||||
return 1;
|
||||
}
|
||||
|
||||
/** FoE read, blocking.
|
||||
*
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number.
|
||||
* @param[in] filename = Filename of file to read.
|
||||
@ -146,7 +146,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
do
|
||||
{
|
||||
{
|
||||
worktodo = FALSE;
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
@ -168,7 +168,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
||||
p = (uint8 *)p + segmentdata;
|
||||
if (segmentdata == maxdata)
|
||||
{
|
||||
worktodo = TRUE;
|
||||
worktodo = TRUE;
|
||||
}
|
||||
FOEp->MbxHeader.length = htoes(0x0006);
|
||||
FOEp->MbxHeader.address = htoes(0x0000);
|
||||
@ -182,7 +182,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
||||
/* send FoE ack to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
if (wkc <= 0)
|
||||
{
|
||||
{
|
||||
worktodo = FALSE;
|
||||
}
|
||||
if (context->FOEhook)
|
||||
@ -217,14 +217,14 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
||||
}
|
||||
*psize = dataread;
|
||||
}
|
||||
} while (worktodo);
|
||||
} while (worktodo);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/** FoE write, blocking.
|
||||
*
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number.
|
||||
* @param[in] filename = Filename of file to write.
|
||||
@ -275,7 +275,7 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
do
|
||||
{
|
||||
{
|
||||
worktodo = FALSE;
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
@ -304,7 +304,7 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
||||
}
|
||||
if(tsize || dofinalzero)
|
||||
{
|
||||
worktodo = TRUE;
|
||||
worktodo = TRUE;
|
||||
dofinalzero = FALSE;
|
||||
segmentdata = tsize;
|
||||
psize -= segmentdata;
|
||||
@ -329,7 +329,7 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
||||
/* send FoE data to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
if (wkc <= 0)
|
||||
{
|
||||
{
|
||||
worktodo = FALSE;
|
||||
}
|
||||
}
|
||||
@ -384,9 +384,9 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
||||
wkc = -EC_ERR_TYPE_PACKET_ERROR;
|
||||
}
|
||||
}
|
||||
} while (worktodo);
|
||||
} while (worktodo);
|
||||
}
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatfoe.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatfoe.c
|
||||
* Headerfile for ethercatfoe.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatfoe_
|
||||
|
@ -63,7 +63,7 @@
|
||||
/** delay in us for eeprom ready loop */
|
||||
#define EC_LOCALDELAY 200
|
||||
|
||||
/** record for ethercat eeprom communications */
|
||||
/** record for ethercat eeprom communications */
|
||||
PACKED_BEGIN
|
||||
typedef struct PACKED
|
||||
{
|
||||
@ -95,7 +95,7 @@ typedef struct PACKED
|
||||
uint16 w1,w2;
|
||||
} ec_emcyt;
|
||||
PACKED_END
|
||||
|
||||
|
||||
#ifdef EC_VER1
|
||||
/** Main slave data array.
|
||||
* Each slave found on the network gets its own record.
|
||||
@ -131,7 +131,7 @@ static ec_eepromFMMUt ec_FMMU;
|
||||
boolean EcatError = FALSE;
|
||||
|
||||
int64 ec_DCtime;
|
||||
|
||||
|
||||
ecx_portt ecx_port;
|
||||
ecx_redportt ecx_redport;
|
||||
|
||||
@ -157,9 +157,9 @@ ecx_contextt ecx_context = {
|
||||
&ec_SM, // .eepSM =
|
||||
&ec_FMMU, // .eepFMMU =
|
||||
NULL // .FOEhook()
|
||||
};
|
||||
};
|
||||
#endif
|
||||
|
||||
|
||||
/** Create list over available network adapters.
|
||||
*
|
||||
* @return First element in list over available network adapters.
|
||||
@ -317,7 +317,7 @@ static void ecx_mbxemergencyerror(ecx_contextt *context, uint16 Slave,uint16 Err
|
||||
}
|
||||
|
||||
/** Initialise lib in single NIC mode
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] ifname = Dev name, f.e. "eth0"
|
||||
* @return >0 if OK
|
||||
*/
|
||||
@ -362,7 +362,7 @@ void ecx_close(ecx_contextt *context)
|
||||
/** 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.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] address = eeprom address in bytes (slave uses words)
|
||||
* @return requested byte, if not available then 0xff
|
||||
@ -471,10 +471,10 @@ int16 ecx_siifind(ecx_contextt *context, uint16 slave, uint16 cat)
|
||||
}
|
||||
|
||||
/** Get string from SII string section in slave EEPROM.
|
||||
* @param[in] context = context struct
|
||||
* @param[out] str = requested string, 0x00 if not found
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] Sn = string number
|
||||
* @param[in] context = context struct
|
||||
* @param[out] str = requested string, 0x00 if not found
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] Sn = string number
|
||||
*/
|
||||
void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
|
||||
{
|
||||
@ -529,9 +529,9 @@ void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn)
|
||||
}
|
||||
|
||||
/** Get FMMU data from SII FMMU section in slave EEPROM.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] FMMU = FMMU struct from SII, max. 4 FMMU's
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] FMMU = FMMU struct from SII, max. 4 FMMU's
|
||||
* @return number of FMMU's defined in section
|
||||
*/
|
||||
uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt* FMMU)
|
||||
@ -569,7 +569,7 @@ uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt* FMMU)
|
||||
}
|
||||
|
||||
/** Get SM data from SII SM section in slave EEPROM.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] SM = first SM struct from SII
|
||||
* @return number of SM's defined in section
|
||||
@ -605,10 +605,10 @@ uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM)
|
||||
}
|
||||
|
||||
/** Get next SM data from SII SM section in slave EEPROM.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] SM = first SM struct from SII
|
||||
* @param[in] n = SM number
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] SM = first SM struct from SII
|
||||
* @param[in] n = SM number
|
||||
* @return >0 if OK
|
||||
*/
|
||||
uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint16 n)
|
||||
@ -639,10 +639,10 @@ uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint
|
||||
}
|
||||
|
||||
/** Get PDO data from SII PDO section in slave EEPROM.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] PDO = PDO struct from SII
|
||||
* @param[in] t = 0=RXPDO 1=TXPDO
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] PDO = PDO struct from SII
|
||||
* @param[in] t = 0=RXPDO 1=TXPDO
|
||||
* @return mapping size in bits of PDO
|
||||
*/
|
||||
int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
@ -751,7 +751,7 @@ int ecx_FPRD_multi(ecx_contextt *context, int n, uint16 *configlst, ec_alstatust
|
||||
}
|
||||
|
||||
/** Read all slave states in ec_slave.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @return lowest state found
|
||||
*/
|
||||
int ecx_readstate(ecx_contextt *context)
|
||||
@ -792,7 +792,7 @@ int ecx_readstate(ecx_contextt *context)
|
||||
context->slavelist[0].ALstatuscode |= context->slavelist[slave].ALstatuscode;
|
||||
}
|
||||
fslave = lslave + 1;
|
||||
} while(lslave < *(context->slavecount));
|
||||
} while(lslave < *(context->slavecount));
|
||||
context->slavelist[0].state = lowest;
|
||||
|
||||
return lowest;
|
||||
@ -800,7 +800,7 @@ int ecx_readstate(ecx_contextt *context)
|
||||
|
||||
/** Write slave state, if slave = 0 then write to all slaves.
|
||||
* The function does not check if the actual state is changed.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number, 0 = master
|
||||
* @return 0
|
||||
*/
|
||||
@ -824,7 +824,7 @@ int ecx_writestate(ecx_contextt *context, uint16 slave)
|
||||
|
||||
/** Check actual slave state.
|
||||
* This is a blocking function.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number, 0 = all slaves
|
||||
* @param[in] reqstate = Requested state
|
||||
* @param[in] timeout = Timout value in us
|
||||
@ -895,7 +895,7 @@ void ec_clearmbx(ec_mbxbuft *Mbx)
|
||||
}
|
||||
|
||||
/** Check if IN mailbox of slave is empty.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] timeout = Timeout in us
|
||||
* @return >0 is success
|
||||
@ -930,7 +930,7 @@ int ecx_mbxempty(ecx_contextt *context, uint16 slave, int timeout)
|
||||
}
|
||||
|
||||
/** Write IN mailbox to slave.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] mbx = Mailbox data
|
||||
* @param[in] timeout = Timeout in us
|
||||
@ -963,7 +963,7 @@ int ecx_mbxsend(ecx_contextt *context, uint16 slave,ec_mbxbuft *mbx, int timeout
|
||||
|
||||
/** Read OUT mailbox from slave.
|
||||
* Supports Mailbox Link Layer with repeat requests.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] mbx = Mailbox data
|
||||
* @param[in] timeout = Timeout in us
|
||||
@ -1058,7 +1058,7 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
|
||||
}
|
||||
|
||||
/** Dump complete EEPROM data from slave in buffer.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] esibuf = EEPROM data buffer, make sure it is big enough.
|
||||
*/
|
||||
@ -1099,7 +1099,7 @@ void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf)
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
@ -1116,7 +1116,7 @@ uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int t
|
||||
}
|
||||
|
||||
/** Write EEPROM to slave bypassing cache.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] data = 16bit data
|
||||
@ -1133,7 +1133,7 @@ int ecx_writeeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, uint16
|
||||
}
|
||||
|
||||
/** Set eeprom control to master. Only if set to PDI.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @return >0 if OK
|
||||
*/
|
||||
@ -1217,7 +1217,7 @@ uint16 ecx_eeprom_waitnotbusyAP(ecx_contextt *context, uint16 aiadr,uint16 *esta
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache. APRD method.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] aiadr = auto increment address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
@ -1296,8 +1296,8 @@ uint64 ecx_readeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, int
|
||||
}
|
||||
|
||||
/** Write EEPROM to slave bypassing cache. APWR method.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] aiadr = configured address of slave
|
||||
* @param[in] context = context struct
|
||||
* @param[in] aiadr = configured address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] data = 16bit data
|
||||
* @param[in] timeout = Timeout in us.
|
||||
@ -1386,7 +1386,7 @@ uint16 ecx_eeprom_waitnotbusyFP(ecx_contextt *context, uint16 configadr,uint16 *
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache. FPRD method.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] configadr = configured address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
@ -1529,7 +1529,7 @@ int ecx_writeeepromFP(ecx_contextt *context, uint16 configadr, uint16 eeproma, u
|
||||
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* Parallel read step 1, make request to slave.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
*/
|
||||
@ -1562,8 +1562,8 @@ void ecx_readeeprom1(ecx_contextt *context, uint16 slave, uint16 eeproma)
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* Parallel read step 2, actual read from slave.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return EEPROM data 32bit
|
||||
*/
|
||||
uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout)
|
||||
@ -1900,101 +1900,225 @@ void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
|
||||
ecx_packeterror(&ecx_context, Slave, Index, SubIdx, ErrorCode);
|
||||
}
|
||||
|
||||
/** Initialise lib in single NIC mode
|
||||
* @param[in] ifname = Dev name, f.e. "eth0"
|
||||
* @return >0 if OK
|
||||
* @see ecx_init
|
||||
*/
|
||||
int ec_init(char * ifname)
|
||||
{
|
||||
return ecx_init(&ecx_context, ifname);
|
||||
}
|
||||
|
||||
/** Initialise lib in redundant NIC mode
|
||||
* @param[in] ifname = Primary Dev name, f.e. "eth0"
|
||||
* @param[in] if2name = Secondary Dev name, f.e. "eth1"
|
||||
* @return >0 if OK
|
||||
* @see ecx_init_redundant
|
||||
*/
|
||||
int ec_init_redundant(char *ifname, char *if2name)
|
||||
{
|
||||
return ecx_init_redundant (&ecx_context, &ecx_redport, ifname, if2name);
|
||||
}
|
||||
|
||||
/** Close lib.
|
||||
* @see ecx_close
|
||||
*/
|
||||
void ec_close(void)
|
||||
{
|
||||
ecx_close(&ecx_context);
|
||||
};
|
||||
|
||||
/** 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.
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] address = eeprom address in bytes (slave uses words)
|
||||
* @return requested byte, if not available then 0xff
|
||||
* @see ecx_siigetbyte
|
||||
*/
|
||||
uint8 ec_siigetbyte(uint16 slave, uint16 address)
|
||||
{
|
||||
return ecx_siigetbyte (&ecx_context, slave, address);
|
||||
}
|
||||
|
||||
/** Find SII section header in slave EEPROM.
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] cat = section category
|
||||
* @return byte address of section at section length entry, if not available then 0
|
||||
* @see ecx_siifind
|
||||
*/
|
||||
int16 ec_siifind(uint16 slave, uint16 cat)
|
||||
{
|
||||
return ecx_siifind (&ecx_context, slave, cat);
|
||||
}
|
||||
|
||||
/** Get string from SII string section in slave EEPROM.
|
||||
* @param[out] str = requested string, 0x00 if not found
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] Sn = string number
|
||||
* @see ecx_siistring
|
||||
*/
|
||||
void ec_siistring(char *str, uint16 slave, uint16 Sn)
|
||||
{
|
||||
ecx_siistring(&ecx_context, str, slave, Sn);
|
||||
}
|
||||
|
||||
/** Get FMMU data from SII FMMU section in slave EEPROM.
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] FMMU = FMMU struct from SII, max. 4 FMMU's
|
||||
* @return number of FMMU's defined in section
|
||||
* @see ecx_siiFMMU
|
||||
*/
|
||||
uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU)
|
||||
{
|
||||
return ecx_siiFMMU (&ecx_context, slave, FMMU);
|
||||
}
|
||||
|
||||
/** Get SM data from SII SM section in slave EEPROM.
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] SM = first SM struct from SII
|
||||
* @return number of SM's defined in section
|
||||
* @see ecx_siiSM
|
||||
*/
|
||||
uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM)
|
||||
{
|
||||
return ecx_siiSM (&ecx_context, slave, SM);
|
||||
}
|
||||
|
||||
/** Get next SM data from SII SM section in slave EEPROM.
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] SM = first SM struct from SII
|
||||
* @param[in] n = SM number
|
||||
* @return >0 if OK
|
||||
* @see ecx_siiSMnext
|
||||
*/
|
||||
uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n)
|
||||
{
|
||||
return ecx_siiSMnext (&ecx_context, slave, SM, n);
|
||||
}
|
||||
|
||||
/** Get PDO data from SII PDO section in slave EEPROM.
|
||||
* @param[in] slave = slave number
|
||||
* @param[out] PDO = PDO struct from SII
|
||||
* @param[in] t = 0=RXPDO 1=TXPDO
|
||||
* @return mapping size in bits of PDO
|
||||
* @see ecx_siiPDO
|
||||
*/
|
||||
int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
{
|
||||
return ecx_siiPDO (&ecx_context, slave, PDO, t);
|
||||
}
|
||||
|
||||
/** Read all slave states in ec_slave.
|
||||
* @return lowest state found
|
||||
* @see ecx_readstate
|
||||
*/
|
||||
int ec_readstate(void)
|
||||
{
|
||||
return ecx_readstate (&ecx_context);
|
||||
}
|
||||
|
||||
/** Write slave state, if slave = 0 then write to all slaves.
|
||||
* The function does not check if the actual state is changed.
|
||||
* @param[in] slave = Slave number, 0 = master
|
||||
* @return 0
|
||||
* @see ecx_writestate
|
||||
*/
|
||||
int ec_writestate(uint16 slave)
|
||||
{
|
||||
return ecx_writestate(&ecx_context, slave);
|
||||
}
|
||||
|
||||
/** Check actual slave state.
|
||||
* This is a blocking function.
|
||||
* @param[in] slave = Slave number, 0 = all slaves
|
||||
* @param[in] reqstate = Requested state
|
||||
* @param[in] timeout = Timout value in us
|
||||
* @return Requested state, or found state after timeout.
|
||||
* @see ecx_statecheck
|
||||
*/
|
||||
uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout)
|
||||
{
|
||||
return ecx_statecheck (&ecx_context, slave, reqstate, timeout);
|
||||
}
|
||||
|
||||
/** Check if IN mailbox of slave is empty.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] timeout = Timeout in us
|
||||
* @return >0 is success
|
||||
* @see ecx_mbxempty
|
||||
*/
|
||||
int ec_mbxempty(uint16 slave, int timeout)
|
||||
{
|
||||
return ecx_mbxempty (&ecx_context, slave, timeout);
|
||||
}
|
||||
|
||||
/** Write IN mailbox to slave.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] mbx = Mailbox data
|
||||
* @param[in] timeout = Timeout in us
|
||||
* @return Work counter (>0 is success)
|
||||
* @see ecx_mbxsend
|
||||
*/
|
||||
int ec_mbxsend(uint16 slave,ec_mbxbuft *mbx, int timeout)
|
||||
{
|
||||
return ecx_mbxsend (&ecx_context, slave, mbx, timeout);
|
||||
}
|
||||
|
||||
/** Read OUT mailbox from slave.
|
||||
* Supports Mailbox Link Layer with repeat requests.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] mbx = Mailbox data
|
||||
* @param[in] timeout = Timeout in us
|
||||
* @return Work counter (>0 is success)
|
||||
* @see ecx_mbxreceive
|
||||
*/
|
||||
int ec_mbxreceive(uint16 slave, ec_mbxbuft *mbx, int timeout)
|
||||
{
|
||||
return ecx_mbxreceive (&ecx_context, slave, mbx, timeout);
|
||||
}
|
||||
|
||||
/** Dump complete EEPROM data from slave in buffer.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[out] esibuf = EEPROM data buffer, make sure it is big enough.
|
||||
* @see ecx_esidump
|
||||
*/
|
||||
void ec_esidump(uint16 slave, uint8 *esibuf)
|
||||
{
|
||||
ecx_esidump (&ecx_context, slave, esibuf);
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return EEPROM data 32bit
|
||||
* @see ecx_readeeprom
|
||||
*/
|
||||
uint32 ec_readeeprom(uint16 slave, uint16 eeproma, int timeout)
|
||||
{
|
||||
return ecx_readeeprom (&ecx_context, slave, eeproma, timeout);
|
||||
}
|
||||
|
||||
/** Write EEPROM to slave bypassing cache.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] data = 16bit data
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return >0 if OK
|
||||
* @see ecx_writeeeprom
|
||||
*/
|
||||
int ec_writeeeprom(uint16 slave, uint16 eeproma, uint16 data, int timeout)
|
||||
{
|
||||
return ecx_writeeeprom (&ecx_context, slave, eeproma, data, timeout);
|
||||
}
|
||||
|
||||
/** Set eeprom control to master. Only if set to PDI.
|
||||
* @param[in] slave = Slave number
|
||||
* @return >0 if OK
|
||||
* @see ecx_eeprom2master
|
||||
*/
|
||||
int ec_eeprom2master(uint16 slave)
|
||||
{
|
||||
return ecx_eeprom2master(&ecx_context, slave);
|
||||
@ -2010,11 +2134,25 @@ uint16 ec_eeprom_waitnotbusyAP(uint16 aiadr,uint16 *estat, int timeout)
|
||||
return ecx_eeprom_waitnotbusyAP (&ecx_context, aiadr, estat, timeout);
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache. APRD method.
|
||||
* @param[in] aiadr = auto increment address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return EEPROM data 64bit or 32bit
|
||||
*/
|
||||
uint64 ec_readeepromAP(uint16 aiadr, uint16 eeproma, int timeout)
|
||||
{
|
||||
return ecx_readeepromAP (&ecx_context, aiadr, eeproma, timeout);
|
||||
}
|
||||
|
||||
/** Write EEPROM to slave bypassing cache. APWR method.
|
||||
* @param[in] aiadr = configured address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] data = 16bit data
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return >0 if OK
|
||||
* @see ecx_writeeepromAP
|
||||
*/
|
||||
int ec_writeeepromAP(uint16 aiadr, uint16 eeproma, uint16 data, int timeout)
|
||||
{
|
||||
return ecx_writeeepromAP (&ecx_context, aiadr, eeproma, data, timeout);
|
||||
@ -2025,31 +2163,80 @@ uint16 ec_eeprom_waitnotbusyFP(uint16 configadr,uint16 *estat, int timeout)
|
||||
return ecx_eeprom_waitnotbusyFP (&ecx_context, configadr, estat, timeout);
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache. FPRD method.
|
||||
* @param[in] configadr = configured address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return EEPROM data 64bit or 32bit
|
||||
* @see ecx_readeepromFP
|
||||
*/
|
||||
uint64 ec_readeepromFP(uint16 configadr, uint16 eeproma, int timeout)
|
||||
{
|
||||
return ecx_readeepromFP (&ecx_context, configadr, eeproma, timeout);
|
||||
}
|
||||
|
||||
/** Write EEPROM to slave bypassing cache. FPWR method.
|
||||
* @param[in] configadr = configured address of slave
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @param[in] data = 16bit data
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return >0 if OK
|
||||
* @see ecx_writeeepromFP
|
||||
*/
|
||||
int ec_writeeepromFP(uint16 configadr, uint16 eeproma, uint16 data, int timeout)
|
||||
{
|
||||
return ecx_writeeepromFP (&ecx_context, configadr, eeproma, data, timeout);
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* Parallel read step 1, make request to slave.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] eeproma = (WORD) Address in the EEPROM
|
||||
* @see ecx_readeeprom1
|
||||
*/
|
||||
void ec_readeeprom1(uint16 slave, uint16 eeproma)
|
||||
{
|
||||
ecx_readeeprom1 (&ecx_context, slave, eeproma);
|
||||
}
|
||||
|
||||
/** Read EEPROM from slave bypassing cache.
|
||||
* Parallel read step 2, actual read from slave.
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return EEPROM data 32bit
|
||||
* @see ecx_readeeprom2
|
||||
*/
|
||||
uint32 ec_readeeprom2(uint16 slave, int timeout)
|
||||
{
|
||||
return ecx_readeeprom2 (&ecx_context, slave, timeout);
|
||||
}
|
||||
|
||||
/** 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.
|
||||
* @param[in] group = group number
|
||||
* @return >0 if processdata is transmitted.
|
||||
* @see ecx_send_processdata_group
|
||||
*/
|
||||
int ec_send_processdata_group(uint8 group)
|
||||
{
|
||||
return ecx_send_processdata_group (&ecx_context, group);
|
||||
}
|
||||
|
||||
/** 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.
|
||||
* @param[in] group = group number
|
||||
* @param[in] timeout = Timeout in us.
|
||||
* @return Work counter.
|
||||
* @see ecx_receive_processdata_group
|
||||
*/
|
||||
int ec_receive_processdata_group(uint8 group, int timeout)
|
||||
{
|
||||
return ecx_receive_processdata_group (&ecx_context, group, timeout);
|
||||
@ -2064,4 +2251,4 @@ int ec_receive_processdata(int timeout)
|
||||
{
|
||||
return ec_receive_processdata_group(0, timeout);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatmain.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatmain.c
|
||||
* Headerfile for ethercatmain.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatmain_
|
||||
@ -95,7 +95,7 @@ typedef struct PACKED
|
||||
uint8 FMMUtype;
|
||||
uint8 FMMUactive;
|
||||
uint8 unused1;
|
||||
uint16 unused2;
|
||||
uint16 unused2;
|
||||
} ec_fmmut;
|
||||
PACKED_END
|
||||
|
||||
@ -216,7 +216,7 @@ typedef struct
|
||||
/** DC receivetimes on port A */
|
||||
int32 DCrtA;
|
||||
/** DC receivetimes on port B */
|
||||
int32 DCrtB;
|
||||
int32 DCrtB;
|
||||
/** DC receivetimes on port C */
|
||||
int32 DCrtC;
|
||||
/** DC receivetimes on port D */
|
||||
@ -327,7 +327,7 @@ typedef struct
|
||||
} ec_eepromSMt;
|
||||
|
||||
/** record to store rxPDO and txPDO table from eeprom */
|
||||
typedef struct
|
||||
typedef struct
|
||||
{
|
||||
uint16 Startpos;
|
||||
uint16 Length;
|
||||
@ -373,7 +373,7 @@ typedef struct
|
||||
} ec_idxstackT;
|
||||
|
||||
/** ringbuf for error storage */
|
||||
typedef struct
|
||||
typedef struct
|
||||
{
|
||||
int16 head;
|
||||
int16 tail;
|
||||
@ -387,7 +387,7 @@ typedef struct PACKED
|
||||
uint8 n;
|
||||
uint8 nu1;
|
||||
uint8 SMtype[EC_MAXSM];
|
||||
} ec_SMcommtypet;
|
||||
} ec_SMcommtypet;
|
||||
PACKED_END
|
||||
|
||||
/** SDO assign structure for CA */
|
||||
@ -397,7 +397,7 @@ typedef struct PACKED
|
||||
uint8 n;
|
||||
uint8 nu1;
|
||||
uint16 index[256];
|
||||
} ec_PDOassignt;
|
||||
} ec_PDOassignt;
|
||||
PACKED_END
|
||||
|
||||
/** SDO description structure for CA */
|
||||
@ -407,7 +407,7 @@ typedef struct PACKED
|
||||
uint8 n;
|
||||
uint8 nu1;
|
||||
uint32 PDO[256];
|
||||
} ec_PDOdesct;
|
||||
} ec_PDOdesct;
|
||||
PACKED_END
|
||||
|
||||
/** Context structure , referenced by all ecx functions*/
|
||||
@ -452,7 +452,7 @@ typedef struct
|
||||
/** internal, SM list from eeprom */
|
||||
ec_eepromSMt *eepSM;
|
||||
/** internal, FMMU list from eeprom */
|
||||
ec_eepromFMMUt *eepFMMU;
|
||||
ec_eepromFMMUt *eepFMMU;
|
||||
/** registered FoE hook */
|
||||
int (*FOEhook)(uint16 slave, int packetnumber, int datasize);
|
||||
} ecx_contextt;
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatprint.c
|
||||
* Version : 1.3.1
|
||||
@ -239,7 +239,7 @@ const ec_soeerrorlist_t ec_soeerrorlist[] = {
|
||||
{0x800A, "No element addressed" },
|
||||
{0xffff, "Unknown" }
|
||||
};
|
||||
|
||||
|
||||
/** MBX error list definition */
|
||||
const ec_mbxerrorlist_t ec_mbxerrorlist[] = {
|
||||
{0x0000, "No error" },
|
||||
@ -264,11 +264,11 @@ const char* ec_sdoerror2string( uint32 sdoerrorcode)
|
||||
int i = 0;
|
||||
|
||||
while ( (ec_sdoerrorlist[i].errorcode != 0xffffffffUL) &&
|
||||
(ec_sdoerrorlist[i].errorcode != sdoerrorcode) )
|
||||
(ec_sdoerrorlist[i].errorcode != sdoerrorcode) )
|
||||
{
|
||||
i++;
|
||||
}
|
||||
|
||||
|
||||
return ec_sdoerrorlist[i].errordescription;
|
||||
}
|
||||
|
||||
@ -281,12 +281,12 @@ char* ec_ALstatuscode2string( uint16 ALstatuscode)
|
||||
{
|
||||
int i = 0;
|
||||
|
||||
while ( (ec_ALstatuscodelist[i].ALstatuscode != 0xffff) &&
|
||||
(ec_ALstatuscodelist[i].ALstatuscode != ALstatuscode) )
|
||||
while ( (ec_ALstatuscodelist[i].ALstatuscode != 0xffff) &&
|
||||
(ec_ALstatuscodelist[i].ALstatuscode != ALstatuscode) )
|
||||
{
|
||||
i++;
|
||||
}
|
||||
|
||||
|
||||
return (char *) ec_ALstatuscodelist[i].ALstatuscodedescription;
|
||||
}
|
||||
|
||||
@ -299,12 +299,12 @@ char* ec_soeerror2string( uint16 errorcode)
|
||||
{
|
||||
int i = 0;
|
||||
|
||||
while ( (ec_soeerrorlist[i].errorcode != 0xffff) &&
|
||||
(ec_soeerrorlist[i].errorcode != errorcode) )
|
||||
while ( (ec_soeerrorlist[i].errorcode != 0xffff) &&
|
||||
(ec_soeerrorlist[i].errorcode != errorcode) )
|
||||
{
|
||||
i++;
|
||||
}
|
||||
|
||||
|
||||
return (char *) ec_soeerrorlist[i].errordescription;
|
||||
}
|
||||
|
||||
@ -317,12 +317,12 @@ char* ec_mbxerror2string( uint16 errorcode)
|
||||
{
|
||||
int i = 0;
|
||||
|
||||
while ( (ec_mbxerrorlist[i].errorcode != 0xffff) &&
|
||||
(ec_mbxerrorlist[i].errorcode != errorcode) )
|
||||
while ( (ec_mbxerrorlist[i].errorcode != 0xffff) &&
|
||||
(ec_mbxerrorlist[i].errorcode != errorcode) )
|
||||
{
|
||||
i++;
|
||||
}
|
||||
|
||||
|
||||
return (char *) ec_mbxerrorlist[i].errordescription;
|
||||
}
|
||||
|
||||
@ -335,7 +335,7 @@ 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) );
|
||||
@ -343,50 +343,50 @@ char* ecx_elist2string(ecx_contextt *context)
|
||||
{
|
||||
case EC_ERR_TYPE_SDO_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
|
||||
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);
|
||||
{
|
||||
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);
|
||||
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",
|
||||
{
|
||||
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",
|
||||
{
|
||||
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));
|
||||
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",
|
||||
sprintf(estring, "%s error:%8.8x\n",
|
||||
timestr, (unsigned)Ec.AbortCode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
return (char*) estring;
|
||||
}
|
||||
else
|
||||
else
|
||||
{
|
||||
return "";
|
||||
}
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatprint.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatprint.c
|
||||
* Headerfile for ethercatprint.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatprint_
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatsoe.c
|
||||
* Version : 1.3.1
|
||||
@ -69,7 +69,7 @@ typedef struct PACKED
|
||||
{
|
||||
uint16 idn;
|
||||
uint16 fragmentsleft;
|
||||
};
|
||||
};
|
||||
} ec_SoEt;
|
||||
PACKED_END
|
||||
|
||||
@ -96,7 +96,7 @@ void ecx_SoEerror(ecx_contextt *context, uint16 Slave, uint16 idn, uint16 Error)
|
||||
}
|
||||
|
||||
/** SoE read, blocking.
|
||||
*
|
||||
*
|
||||
* The IDN object of the selected slave and DriveNo is read. If a response
|
||||
* is larger than the mailbox size then the response is segmented. The function
|
||||
* will combine all segments and copy them to the parameter buffer.
|
||||
@ -151,7 +151,7 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
while (NotLast)
|
||||
{
|
||||
{
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* read slave response */
|
||||
@ -181,14 +181,14 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
||||
totalsize = *psize;
|
||||
/* copy parameter data in parameter buffer */
|
||||
if (framedatasize > 0) memcpy(bp, mp, framedatasize);
|
||||
}
|
||||
}
|
||||
|
||||
if (!aSoEp->incomplete)
|
||||
if (!aSoEp->incomplete)
|
||||
{
|
||||
NotLast = FALSE;
|
||||
*psize = totalsize;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
/* other slave response */
|
||||
else
|
||||
{
|
||||
@ -212,14 +212,14 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
||||
{
|
||||
NotLast = FALSE;
|
||||
ecx_packeterror(context, slave, idn, 0, 4); /* no response */
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** SoE write, blocking.
|
||||
*
|
||||
*
|
||||
* The IDN object of the selected slave and DriveNo is written. If a response
|
||||
* is larger than the mailbox size then the response is segmented.
|
||||
*
|
||||
@ -262,7 +262,7 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
||||
maxdata = context->slavelist[slave].mbx_l - sizeof(ec_SoEt);
|
||||
NotLast = TRUE;
|
||||
while (NotLast)
|
||||
{
|
||||
{
|
||||
framedatasize = psize;
|
||||
NotLast = FALSE;
|
||||
SoEp->idn = htoes(idn);
|
||||
@ -288,7 +288,7 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
if (!NotLast || !ecx_mbxempty(context, slave, timeout))
|
||||
{
|
||||
{
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* read slave response */
|
||||
@ -304,7 +304,7 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
||||
(aSoEp->elementflags == elementflags))
|
||||
{
|
||||
/* SoE write succeeded */
|
||||
}
|
||||
}
|
||||
/* other slave response */
|
||||
else
|
||||
{
|
||||
@ -326,9 +326,9 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
||||
else
|
||||
{
|
||||
ecx_packeterror(context, slave, idn, 0, 4); /* no response */
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
}
|
||||
@ -365,7 +365,7 @@ int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
||||
if ((wkc > 0) && (psize >= 4) && ((entries = etohs(SoEmapping.currentlength) / 2) > 0) && (entries <= EC_SOE_MAXMAPPING))
|
||||
{
|
||||
/* command word (uint16) is always mapped but not in list */
|
||||
*Osize = 16;
|
||||
*Osize = 16;
|
||||
for (itemcount = 0 ; itemcount < entries ; itemcount++)
|
||||
{
|
||||
psize = sizeof(SoEattribute);
|
||||
@ -375,16 +375,16 @@ int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
||||
{
|
||||
/* length : 0 = 8bit, 1 = 16bit .... */
|
||||
*Osize += (int)8 << SoEattribute.length;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
psize = sizeof(SoEmapping);
|
||||
/* read input mapping via SoE */
|
||||
wkc = ecx_SoEread(context, slave, driveNr, EC_SOE_VALUE_B, EC_IDN_ATCONFIG, &psize, &SoEmapping, EC_TIMEOUTRXM);
|
||||
if ((wkc > 0) && (psize >= 4) && ((entries = etohs(SoEmapping.currentlength) / 2) > 0) && (entries <= EC_SOE_MAXMAPPING))
|
||||
{
|
||||
/* status word (uint16) is always mapped but not in list */
|
||||
*Isize = 16;
|
||||
*Isize = 16;
|
||||
for (itemcount = 0 ; itemcount < entries ; itemcount++)
|
||||
{
|
||||
psize = sizeof(SoEattribute);
|
||||
@ -394,9 +394,9 @@ int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
||||
{
|
||||
/* length : 0 = 8bit, 1 = 16bit .... */
|
||||
*Isize += (int)8 << SoEattribute.length;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* found some I/O bits ? */
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatsoe.h
|
||||
* Version : 1.3.1
|
||||
@ -39,9 +39,9 @@
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/** \file
|
||||
/** \file
|
||||
* \brief
|
||||
* Headerfile for ethercatsoe.c
|
||||
* Headerfile for ethercatsoe.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercatsoe_
|
||||
@ -88,12 +88,12 @@ typedef struct PACKED
|
||||
/** maximum length in bytes of list */
|
||||
uint16 maxlength;
|
||||
union
|
||||
{
|
||||
{
|
||||
uint8 byte[8];
|
||||
uint16 word[4];
|
||||
uint32 dword[2];
|
||||
uint64 lword[1];
|
||||
};
|
||||
};
|
||||
} ec_SoElistt;
|
||||
PACKED_END
|
||||
|
||||
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercattype.h
|
||||
* Version : 1.3.1
|
||||
@ -40,7 +40,7 @@
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* \brief
|
||||
* General typedefs and defines for EtherCAT.
|
||||
*
|
||||
* Defines that could need optimalisation for specific applications
|
||||
@ -48,7 +48,7 @@
|
||||
* standard linux PC or laptop and a wired connection to maximal 100 slaves.
|
||||
* For use with wireless connections or lots of slaves the timouts need
|
||||
* increasing. For fast systems running Xenomai and RT-net or alike the
|
||||
* timeouts need to be shorter.
|
||||
* timeouts need to be shorter.
|
||||
*/
|
||||
|
||||
#ifndef _EC_TYPE_H
|
||||
@ -242,7 +242,7 @@ typedef enum
|
||||
} ec_datatype;
|
||||
|
||||
/** Ethercat command types */
|
||||
typedef enum
|
||||
typedef enum
|
||||
{
|
||||
/** No operation */
|
||||
EC_CMD_NOP = 0x00,
|
||||
@ -278,7 +278,7 @@ typedef enum
|
||||
} ec_cmdtype;
|
||||
|
||||
/** Ethercat EEprom command types */
|
||||
typedef enum
|
||||
typedef enum
|
||||
{
|
||||
/** No operation */
|
||||
EC_ECMD_NOP = 0x0000,
|
||||
@ -411,7 +411,7 @@ enum
|
||||
};
|
||||
|
||||
/** Ethercat registers */
|
||||
enum
|
||||
enum
|
||||
{
|
||||
ECT_REG_TYPE = 0x0000,
|
||||
ECT_REG_PORTDES = 0x0007,
|
||||
|
@ -124,7 +124,7 @@ static ecx_contextt ctx [] = {
|
||||
&ec_PDOassign,
|
||||
&ec_PDOdesc,
|
||||
&ec_SM,
|
||||
&ec_FMMU
|
||||
&ec_FMMU
|
||||
},
|
||||
{
|
||||
&ecx_port2,
|
||||
@ -160,23 +160,23 @@ void slaveinfo(char *ifname)
|
||||
int chk;
|
||||
volatile int wkc[2];
|
||||
boolean inOP;
|
||||
|
||||
|
||||
printf("Starting slaveinfo\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ecx_init(&ctx[0],"ie1g1") && ecx_init(&ctx[1],"ie1g0"))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ecx_config_init(&ctx[0],FALSE) > 0 && ecx_config_init(&ctx[1],FALSE) > 0 )
|
||||
{
|
||||
for (ctx_count = 0; ctx_count < 2; ctx_count++)
|
||||
for (ctx_count = 0; ctx_count < 2; ctx_count++)
|
||||
{
|
||||
ecx_config_map_group(&ctx[ctx_count], IOmap, 0);
|
||||
ecx_configdc(&ctx[ctx_count]);
|
||||
while(*(ctx[ctx_count].ecaterror)) printf("%s", ecx_elist2string(&ctx[ctx_count]));
|
||||
printf("%d slaves found and configured.\n",*(ctx[ctx_count].slavecount));
|
||||
expectedWKC[ctx_count] = ( ctx[ctx_count].grouplist[0].outputsWKC * 2) + ctx[ctx_count].grouplist[0].inputsWKC;
|
||||
expectedWKC[ctx_count] = ( ctx[ctx_count].grouplist[0].outputsWKC * 2) + ctx[ctx_count].grouplist[0].inputsWKC;
|
||||
printf("Calculated workcounter %d\n", expectedWKC[ctx_count]);
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ecx_statecheck(&ctx[ctx_count],0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 3);
|
||||
@ -200,36 +200,36 @@ void slaveinfo(char *ifname)
|
||||
printf("\nSlave:%d\n Name:%s\n Output size: %dbits\n Input size: %dbits\n State: %d\n Delay: %d[ns]\n Has DC: %d\n",
|
||||
cnt, ctx[ctx_count].slavelist[cnt].name, ctx[ctx_count].slavelist[cnt].Obits, ctx[ctx_count].slavelist[cnt].Ibits,
|
||||
ctx[ctx_count].slavelist[cnt].state, ctx[ctx_count].slavelist[cnt].pdelay, ctx[ctx_count].slavelist[cnt].hasdc);
|
||||
if (ctx[ctx_count].slavelist[cnt].hasdc)
|
||||
if (ctx[ctx_count].slavelist[cnt].hasdc)
|
||||
{
|
||||
printf(" DCParentport:%d\n", ctx[ctx_count].slavelist[cnt].parentport);
|
||||
}
|
||||
printf(" Activeports:%d.%d.%d.%d\n", (ctx[ctx_count].slavelist[cnt].activeports & 0x01) > 0 ,
|
||||
(ctx[ctx_count].slavelist[cnt].activeports & 0x02) > 0 ,
|
||||
(ctx[ctx_count].slavelist[cnt].activeports & 0x04) > 0 ,
|
||||
(ctx[ctx_count].slavelist[cnt].activeports & 0x02) > 0 ,
|
||||
(ctx[ctx_count].slavelist[cnt].activeports & 0x04) > 0 ,
|
||||
(ctx[ctx_count].slavelist[cnt].activeports & 0x08) > 0 );
|
||||
printf(" Configured address: %4.4x\n", ctx[ctx_count].slavelist[cnt].configadr);
|
||||
printf(" Man: %8.8x ID: %8.8x Rev: %8.8x\n", (int)ctx[ctx_count].slavelist[cnt].eep_man,
|
||||
printf(" Man: %8.8x ID: %8.8x Rev: %8.8x\n", (int)ctx[ctx_count].slavelist[cnt].eep_man,
|
||||
(int)ctx[ctx_count].slavelist[cnt].eep_id, (int)ctx[ctx_count].slavelist[cnt].eep_rev);
|
||||
for(nSM = 0 ; nSM < EC_MAXSM ; nSM++)
|
||||
{
|
||||
if(ctx[ctx_count].slavelist[cnt].SM[nSM].StartAddr > 0)
|
||||
printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, ctx[ctx_count].slavelist[cnt].SM[nSM].StartAddr,
|
||||
ctx[ctx_count].slavelist[cnt].SM[nSM].SMlength,(int)ctx[ctx_count].slavelist[cnt].SM[nSM].SMflags,
|
||||
printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, ctx[ctx_count].slavelist[cnt].SM[nSM].StartAddr,
|
||||
ctx[ctx_count].slavelist[cnt].SM[nSM].SMlength,(int)ctx[ctx_count].slavelist[cnt].SM[nSM].SMflags,
|
||||
ctx[ctx_count].slavelist[cnt].SMtype[nSM]);
|
||||
}
|
||||
for(j = 0 ; j < ctx[ctx_count].slavelist[cnt].FMMUunused ; j++)
|
||||
{
|
||||
printf(" FMMU%1d Ls:%8.8x Ll:%4d Lsb:%d Leb:%d Ps:%4.4x Psb:%d Ty:%2.2x Act:%2.2x\n", j,
|
||||
(int)ctx[ctx_count].slavelist[cnt].FMMU[j].LogStart, ctx[ctx_count].slavelist[cnt].FMMU[j].LogLength,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU[j].LogStartbit, ctx[ctx_count].slavelist[cnt].FMMU[j].LogEndbit,
|
||||
(int)ctx[ctx_count].slavelist[cnt].FMMU[j].LogStart, ctx[ctx_count].slavelist[cnt].FMMU[j].LogLength,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU[j].LogStartbit, ctx[ctx_count].slavelist[cnt].FMMU[j].LogEndbit,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU[j].PhysStart, ctx[ctx_count].slavelist[cnt].FMMU[j].PhysStartBit,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU[j].FMMUtype, ctx[ctx_count].slavelist[cnt].FMMU[j].FMMUactive);
|
||||
}
|
||||
printf(" FMMUfunc 0:%d 1:%d 2:%d 3:%d\n",
|
||||
ctx[ctx_count].slavelist[cnt].FMMU0func, ctx[ctx_count].slavelist[cnt].FMMU2func, ctx[ctx_count].slavelist[cnt].FMMU2func,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU0func, ctx[ctx_count].slavelist[cnt].FMMU2func, ctx[ctx_count].slavelist[cnt].FMMU2func,
|
||||
ctx[ctx_count].slavelist[cnt].FMMU3func);
|
||||
printf(" MBX length wr: %d rd: %d MBX protocols : %2.2x\n", ctx[ctx_count].slavelist[cnt].mbx_l,
|
||||
printf(" MBX length wr: %d rd: %d MBX protocols : %2.2x\n", ctx[ctx_count].slavelist[cnt].mbx_l,
|
||||
ctx[ctx_count].slavelist[cnt].mbx_rl, ctx[ctx_count].slavelist[cnt].mbx_proto);
|
||||
ssigen = ecx_siifind(&ctx[ctx_count], cnt, ECT_SII_GENERAL);
|
||||
/* SII general section */
|
||||
@ -242,8 +242,8 @@ void slaveinfo(char *ifname)
|
||||
if((ecx_siigetbyte(&ctx[ctx_count], cnt, ssigen + 0x0d) & 0x02) > 0)
|
||||
{
|
||||
ctx[ctx_count].slavelist[cnt].blockLRW = 1;
|
||||
ctx[ctx_count].slavelist[0].blockLRW++;
|
||||
}
|
||||
ctx[ctx_count].slavelist[0].blockLRW++;
|
||||
}
|
||||
ctx[ctx_count].slavelist[cnt].Ebuscurrent = ecx_siigetbyte(&ctx[ctx_count], cnt, ssigen + 0x0e);
|
||||
ctx[ctx_count].slavelist[cnt].Ebuscurrent += ecx_siigetbyte(&ctx[ctx_count], cnt, ssigen + 0x0f) << 8;
|
||||
ctx[ctx_count].slavelist[0].Ebuscurrent += ctx[ctx_count].slavelist[cnt].Ebuscurrent;
|
||||
@ -254,9 +254,9 @@ void slaveinfo(char *ifname)
|
||||
ctx[ctx_count].slavelist[cnt].Ebuscurrent, ctx[ctx_count].slavelist[cnt].blockLRW);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
inOP = FALSE;
|
||||
|
||||
|
||||
printf("Request operational state for all slaves\n");
|
||||
expectedWKC[0] = (ctx[0].grouplist[0].outputsWKC * 2) + ctx[0].grouplist[0].inputsWKC;
|
||||
expectedWKC[1] = (ctx[1].grouplist[0].outputsWKC * 2) + ctx[1].grouplist[0].inputsWKC;
|
||||
@ -330,8 +330,8 @@ void slaveinfo(char *ifname)
|
||||
}
|
||||
stop_RT_trace ();
|
||||
inOP = FALSE;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -345,24 +345,24 @@ void slaveinfo(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void main(int argc, char* argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nSlaveinfo\n");
|
||||
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
/* start slaveinfo */
|
||||
slaveinfo(argv[1]);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Usage: slaveinfo ifname [options]\nifname = eth0 for example\nOptions :\n -sdo : print SDO info\n -map : print mapping\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
}
|
||||
|
@ -11,7 +11,7 @@
|
||||
* -i display EEPROM information
|
||||
* -walias write slave alias in EEPROM
|
||||
*
|
||||
* (c)Arthur Ketels 2010-2012
|
||||
* (c)Arthur Ketels 2010-2012
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -60,30 +60,30 @@ char sline[MAXSLENGTH];
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (cc < MAXBUF))
|
||||
ebuf[cc++] = (uint8)c;
|
||||
*length = cc;
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int input_intelhex(char *fname, int *start, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int c, sc, retval = 1;
|
||||
int ll, ladr, lt, sn, i, lval;
|
||||
int hstart, hlength, sum;
|
||||
|
||||
fp = fopen(fname, "r");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
hstart = MAXBUF;
|
||||
hlength = 0;
|
||||
@ -124,7 +124,7 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
printf("Invalid checksum.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
while (c != EOF);
|
||||
if (retval)
|
||||
@ -133,34 +133,34 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
*start = hstart;
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
int output_bin(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc;
|
||||
|
||||
fp = fopen(fname, "wb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
for (cc = 0 ; cc < length ; cc++)
|
||||
fputc( ebuf[cc], fp);
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int output_intelhex(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, ll, sum, i;
|
||||
|
||||
fp = fopen(fname, "w");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (cc < length)
|
||||
{
|
||||
@ -176,9 +176,9 @@ int output_intelhex(char *fname, int length)
|
||||
fprintf(fp, "%2.2X\n", (0x100 - sum) & 0xff);
|
||||
cc += ll;
|
||||
}
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -189,7 +189,7 @@ int eeprom_read(int slave, int start, int length)
|
||||
uint32 b4;
|
||||
uint64 b8;
|
||||
uint8 eepctl;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -229,10 +229,10 @@ int eeprom_read(int slave, int start, int length)
|
||||
ebuf[i+3] = b4 >> 24;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -242,7 +242,7 @@ int eeprom_write(int slave, int start, int length)
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -263,10 +263,10 @@ int eeprom_write(int slave, int start, int length)
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -276,7 +276,7 @@ int eeprom_writealias(int slave, int alias)
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && (alias <= 0xffff))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -286,10 +286,10 @@ int eeprom_writealias(int slave, int alias)
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl , EC_TIMEOUTRET); /* set Eeprom to master */
|
||||
|
||||
ret = ec_writeeepromAP(aiadr, 0x04 , alias, EC_TIMEOUTEEP);
|
||||
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -297,10 +297,10 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
{
|
||||
int w, rc = 0, estart, esize;
|
||||
uint16 *wbuf;
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
|
||||
w = 0x0000;
|
||||
@ -352,7 +352,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
if (mode == MODE_WRITEBIN) rc = input_bin(fname, &esize);
|
||||
|
||||
if (rc > 0)
|
||||
{
|
||||
{
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
printf("Slave %d\n", slave);
|
||||
printf(" Vendor ID : %8.8X\n",*(uint32 *)(wbuf + 0x08));
|
||||
@ -364,20 +364,20 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
fflush(stdout);
|
||||
rc = gettimeofday(&tstart, NULL);
|
||||
eeprom_write(slave, estart, esize);
|
||||
rc = gettimeofday(&tend, NULL);
|
||||
rc = gettimeofday(&tend, NULL);
|
||||
timersub(&tend, &tstart, &tdif);
|
||||
|
||||
printf("\nTotal EEPROM write time :%ldms\n", (tdif.tv_usec+(tdif.tv_sec*1000000L)) / 1000);
|
||||
}
|
||||
else
|
||||
printf("Error reading file, abort.\n");
|
||||
printf("Error reading file, abort.\n");
|
||||
}
|
||||
if (mode == MODE_WRITEALIAS)
|
||||
{
|
||||
if(eeprom_writealias(slave, alias))
|
||||
printf("Alias %4.4X written successfully to slave %d\n");
|
||||
else
|
||||
printf("Alias not written\n");
|
||||
printf("Alias not written\n");
|
||||
}
|
||||
}
|
||||
else
|
||||
@ -391,7 +391,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
}
|
||||
else
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
@ -399,9 +399,9 @@ int main(int argc, char *argv[])
|
||||
|
||||
mode = MODE_NONE;
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
slave = atoi(argv[2]);
|
||||
if ((strncmp(argv[3], "-i", sizeof("-i")) == 0)) mode = MODE_INFO;
|
||||
if ((strncmp(argv[3], "-i", sizeof("-i")) == 0)) mode = MODE_INFO;
|
||||
if (argc > 4)
|
||||
{
|
||||
if ((strncmp(argv[3], "-r", sizeof("-r")) == 0)) mode = MODE_READBIN;
|
||||
@ -428,9 +428,9 @@ int main(int argc, char *argv[])
|
||||
printf(" -ri read EEPROM, output Intel Hex format\n");
|
||||
printf(" -w write EEPROM, input binary format\n");
|
||||
printf(" -wi write EEPROM, input Intel Hex format\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
@ -7,7 +7,7 @@
|
||||
*
|
||||
* This test is specifically build for the E/BOX.
|
||||
*
|
||||
* (c)Arthur Ketels 2011
|
||||
* (c)Arthur Ketels 2011
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -39,13 +39,13 @@ typedef struct PACKED
|
||||
int32 ain[2];
|
||||
uint32 tsain;
|
||||
int32 enc[2];
|
||||
} in_EBOXt;
|
||||
} in_EBOXt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
uint8 counter;
|
||||
int16 stream[100];
|
||||
} in_EBOX_streamt;
|
||||
} in_EBOX_streamt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
@ -53,12 +53,12 @@ typedef struct PACKED
|
||||
uint8 dout;
|
||||
int16 aout[2];
|
||||
uint16 pwmout[2];
|
||||
} out_EBOXt;
|
||||
} out_EBOXt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
uint8 control;
|
||||
} out_EBOX_streamt;
|
||||
} out_EBOX_streamt;
|
||||
|
||||
// total samples to capture
|
||||
#define MAXSTREAM 200000
|
||||
@ -93,30 +93,30 @@ int16 stream2[MAXSTREAM];
|
||||
int output_cvs(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int i;
|
||||
|
||||
fp = fopen(fname, "w");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
for (i = 0; i < length; i++)
|
||||
{
|
||||
fprintf(fp, "%d %d %d\n", i, stream1[i], stream2[i]);
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
void eboxtest(char *ifname)
|
||||
{
|
||||
int cnt, i;
|
||||
|
||||
|
||||
printf("Starting E/BOX test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
@ -130,9 +130,9 @@ void eboxtest(char *ifname)
|
||||
// reprogram PDO mapping to set slave in stream mode
|
||||
// this can only be done in pre-OP state
|
||||
os=sizeof(ob2); ob2 = 0x1601;
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
os=sizeof(ob2); ob2 = 0x1a01;
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
}
|
||||
|
||||
ec_config_map(&IOmap);
|
||||
@ -141,10 +141,10 @@ void eboxtest(char *ifname)
|
||||
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
|
||||
|
||||
/* configure DC options for every DC capable slave found in the list */
|
||||
printf("DC capable : %d\n",ec_configdc());
|
||||
|
||||
|
||||
/* check configuration */
|
||||
if (( ec_slavecount >= 1 ) &&
|
||||
(strcmp(ec_slave[1].name,"E/BOX") == 0)
|
||||
@ -166,10 +166,10 @@ void eboxtest(char *ifname)
|
||||
}
|
||||
printf("Request operational state for all slaves\n");
|
||||
|
||||
/* send one processdata cycle to init SM in slaves */
|
||||
/* send one processdata cycle to init SM in slaves */
|
||||
ec_send_processdata();
|
||||
ec_receive_processdata(EC_TIMEOUTRET);
|
||||
|
||||
|
||||
ec_slave[0].state = EC_STATE_OPERATIONAL;
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
@ -202,12 +202,12 @@ void eboxtest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("Not all slaves reached operational state.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("E/BOX not found in slave configuration.\n");
|
||||
}
|
||||
}
|
||||
ec_dcsync0(1, FALSE, 8000, 0); // SYNC0 off
|
||||
printf("Request safe operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_SAFE_OP;
|
||||
@ -226,9 +226,9 @@ void eboxtest(char *ifname)
|
||||
// restore PDO to standard mode
|
||||
// this can only be done is pre-op state
|
||||
os=sizeof(ob2); ob2 = 0x1600;
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
os=sizeof(ob2); ob2 = 0x1a00;
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
}
|
||||
printf("Streampos %d\n", streampos);
|
||||
output_cvs("stream.txt", streampos);
|
||||
@ -244,25 +244,25 @@ void eboxtest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* add ns to timespec */
|
||||
void add_timespec(struct timespec *ts, int64 addtime)
|
||||
{
|
||||
int64 sec, nsec;
|
||||
|
||||
|
||||
nsec = addtime % NSEC_PER_SEC;
|
||||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_nsec = nsec;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* PI calculation to get linux time synced to DC time */
|
||||
void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
@ -274,7 +274,7 @@ void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
if(delta>0){ integral++; }
|
||||
if(delta<0){ integral--; }
|
||||
*offsettime = -(delta / 100) - (integral /20);
|
||||
}
|
||||
}
|
||||
|
||||
/* RT EtherCAT thread */
|
||||
void ecatthread( void *ptr )
|
||||
@ -285,7 +285,7 @@ void ecatthread( void *ptr )
|
||||
int i;
|
||||
int pcounter = 0;
|
||||
int64 cycletime;
|
||||
|
||||
|
||||
pthread_mutex_lock(&mutex);
|
||||
gettimeofday(&tp, NULL);
|
||||
|
||||
@ -297,7 +297,7 @@ void ecatthread( void *ptr )
|
||||
toff = 0;
|
||||
dorun = 0;
|
||||
while(1)
|
||||
{
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
add_timespec(&ts, cycletime + toff);
|
||||
/* wait to cycle start */
|
||||
@ -312,7 +312,7 @@ void ecatthread( void *ptr )
|
||||
|
||||
cyclecount++;
|
||||
|
||||
|
||||
|
||||
if((in_EBOX->counter != pcounter) && (streampos < (MAXSTREAM - 1)))
|
||||
{
|
||||
// check if we have timing problems in master
|
||||
@ -335,11 +335,11 @@ void ecatthread( void *ptr )
|
||||
}
|
||||
pcounter = in_EBOX->counter;
|
||||
}
|
||||
|
||||
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
@ -347,9 +347,9 @@ int main(int argc, char *argv[])
|
||||
int ctime;
|
||||
struct sched_param param;
|
||||
int policy = SCHED_OTHER;
|
||||
|
||||
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nE/BOX test\n");
|
||||
|
||||
|
||||
memset(&schedp, 0, sizeof(schedp));
|
||||
/* do not set priority above 49, otherwise sockets are starved */
|
||||
schedp.sched_priority = 30;
|
||||
@ -360,16 +360,16 @@ int main(int argc, char *argv[])
|
||||
usleep(1000);
|
||||
}
|
||||
while (dorun);
|
||||
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
dorun = 1;
|
||||
if( argc > 2)
|
||||
ctime = atoi(argv[2]);
|
||||
else
|
||||
ctime = 1000; // 1ms cycle time
|
||||
/* create RT thread */
|
||||
pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
memset(¶m, 0, sizeof(param));
|
||||
/* give it higher priority */
|
||||
param.sched_priority = 40;
|
||||
@ -381,12 +381,12 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
printf("Usage: ebox ifname [cycletime]\nifname = eth0 for example\ncycletime in us\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
schedp.sched_priority = 0;
|
||||
sched_setscheduler(0, SCHED_OTHER, &schedp);
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
@ -11,7 +11,7 @@
|
||||
* -i display EEPROM information
|
||||
* -walias write slave alias in EEPROM
|
||||
*
|
||||
* (c)Arthur Ketels 2010-2012
|
||||
* (c)Arthur Ketels 2010-2012
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -65,49 +65,49 @@ void calc_crc(uint8 *crc, uint8 b)
|
||||
*crc = (*crc << 1) ^ 0x07;
|
||||
else
|
||||
*crc = (*crc << 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint16 SIIcrc(uint8 *buf)
|
||||
{
|
||||
int i;
|
||||
int i;
|
||||
uint8 crc;
|
||||
|
||||
crc = 0xff;
|
||||
|
||||
crc = 0xff;
|
||||
for( i = 0 ; i <= 13 ; i++ )
|
||||
{
|
||||
calc_crc(&crc , *(buf++));
|
||||
}
|
||||
calc_crc(&crc , *(buf++));
|
||||
}
|
||||
return (uint16)crc;
|
||||
}
|
||||
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (cc < MAXBUF))
|
||||
ebuf[cc++] = (uint8)c;
|
||||
*length = cc;
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int input_intelhex(char *fname, int *start, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int c, sc, retval = 1;
|
||||
int ll, ladr, lt, sn, i, lval;
|
||||
int hstart, hlength, sum;
|
||||
|
||||
fp = fopen(fname, "r");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
hstart = MAXBUF;
|
||||
hlength = 0;
|
||||
@ -148,7 +148,7 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
printf("Invalid checksum.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
while (c != EOF);
|
||||
if (retval)
|
||||
@ -157,34 +157,34 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
*start = hstart;
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
int output_bin(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc;
|
||||
|
||||
fp = fopen(fname, "wb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
for (cc = 0 ; cc < length ; cc++)
|
||||
fputc( ebuf[cc], fp);
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int output_intelhex(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, ll, sum, i;
|
||||
|
||||
fp = fopen(fname, "w");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (cc < length)
|
||||
{
|
||||
@ -200,9 +200,9 @@ int output_intelhex(char *fname, int length)
|
||||
fprintf(fp, "%2.2X\n", (0x100 - sum) & 0xff);
|
||||
cc += ll;
|
||||
}
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -213,7 +213,7 @@ int eeprom_read(int slave, int start, int length)
|
||||
uint32 b4;
|
||||
uint64 b8;
|
||||
uint8 eepctl;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -253,10 +253,10 @@ int eeprom_read(int slave, int start, int length)
|
||||
ebuf[i+3] = b4 >> 24;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -265,7 +265,7 @@ int eeprom_write(int slave, int start, int length)
|
||||
int i, dc = 0;
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -286,10 +286,10 @@ int eeprom_write(int slave, int start, int length)
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -298,7 +298,7 @@ int eeprom_writealias(int slave, int alias, uint16 crc)
|
||||
uint16 aiadr;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && (alias <= 0xffff))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -310,10 +310,10 @@ int eeprom_writealias(int slave, int alias, uint16 crc)
|
||||
ret = ec_writeeepromAP(aiadr, 0x04 , alias, EC_TIMEOUTEEP);
|
||||
if (ret)
|
||||
ret = ec_writeeepromAP(aiadr, 0x07 , crc, EC_TIMEOUTEEP);
|
||||
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -321,10 +321,10 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
{
|
||||
int w, rc = 0, estart, esize;
|
||||
uint16 *wbuf;
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
|
||||
w = 0x0000;
|
||||
@ -347,7 +347,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
printf(" PDI Config : %4.4X\n",*(wbuf + 0x01));
|
||||
printf(" Config Alias : %4.4X\n",*(wbuf + 0x04));
|
||||
printf(" Checksum : %4.4X\n",*(wbuf + 0x07));
|
||||
printf(" calculated : %4.4X\n",SIIcrc(&ebuf[0]));
|
||||
printf(" calculated : %4.4X\n",SIIcrc(&ebuf[0]));
|
||||
printf(" Vendor ID : %8.8X\n",*(uint32 *)(wbuf + 0x08));
|
||||
printf(" Product Code : %8.8X\n",*(uint32 *)(wbuf + 0x0A));
|
||||
printf(" Revision Number : %8.8X\n",*(uint32 *)(wbuf + 0x0C));
|
||||
@ -377,7 +377,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
if (mode == MODE_WRITEBIN) rc = input_bin(fname, &esize);
|
||||
|
||||
if (rc > 0)
|
||||
{
|
||||
{
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
printf("Slave %d\n", slave);
|
||||
printf(" Vendor ID : %8.8X\n",*(uint32 *)(wbuf + 0x08));
|
||||
@ -395,26 +395,26 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
printf("\nTotal EEPROM write time :%ldms\n", (tdif.usec+(tdif.sec*1000000L)) / 1000);
|
||||
}
|
||||
else
|
||||
printf("Error reading file, abort.\n");
|
||||
printf("Error reading file, abort.\n");
|
||||
}
|
||||
if (mode == MODE_WRITEALIAS)
|
||||
{
|
||||
if( eeprom_read(slave, 0x0000, CRCBUF) ) // read first 14 bytes
|
||||
{
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
*(wbuf + 0x04) = alias;
|
||||
*(wbuf + 0x04) = alias;
|
||||
if(eeprom_writealias(slave, alias, SIIcrc(&ebuf[0])))
|
||||
{
|
||||
printf("Alias %4.4X written successfully to slave %d\n", alias, slave);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Alias not written\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Could not read slave EEPROM");
|
||||
printf("Could not read slave EEPROM");
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -435,7 +435,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
@ -443,7 +443,7 @@ int main(int argc, char *argv[])
|
||||
|
||||
mode = MODE_NONE;
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
slave = atoi(argv[2]);
|
||||
if ((strncmp(argv[3], "-i", sizeof("-i")) == 0)) mode = MODE_INFO;
|
||||
if (argc > 4)
|
||||
@ -472,9 +472,9 @@ int main(int argc, char *argv[])
|
||||
printf(" -ri read EEPROM, output Intel Hex format\n");
|
||||
printf(" -w write EEPROM, input binary format\n");
|
||||
printf(" -wi write EEPROM, input Intel Hex format\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
@ -41,11 +41,11 @@ uint16 argslave;
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (cc < FWBUFSIZE))
|
||||
filebuffer[cc++] = (uint8)c;
|
||||
@ -56,12 +56,12 @@ int input_bin(char *fname, int *length)
|
||||
|
||||
|
||||
void boottest(char *ifname, uint16 slave, char *filename)
|
||||
{
|
||||
{
|
||||
printf("Starting firmware update example\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
|
||||
@ -69,7 +69,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
{
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
|
||||
|
||||
printf("Request init state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_INIT;
|
||||
ec_writestate(slave);
|
||||
@ -104,7 +104,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
|
||||
/* program SM1 mailbox out for slave */
|
||||
ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM1, sizeof(ec_smt), &ec_slave[slave].SM[1], EC_TIMEOUTRET);
|
||||
|
||||
|
||||
printf("Request BOOT state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_BOOT;
|
||||
ec_writestate(slave);
|
||||
@ -140,15 +140,15 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nFirmware update example\n");
|
||||
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
argslave = atoi(argv[2]);
|
||||
boottest(argv[1], argslave, argv[3]);
|
||||
}
|
||||
@ -159,8 +159,8 @@ int main(int argc, char *argv[])
|
||||
printf("slave = slave number in EtherCAT order 1..n\n");
|
||||
printf("fname = binary file to store in slave\n");
|
||||
printf("CAUTION! Using the wrong file can result in a bricked slave!\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
||||
|
@ -7,7 +7,7 @@
|
||||
*
|
||||
* This is a redundancy test.
|
||||
*
|
||||
* (c)Arthur Ketels 2008
|
||||
* (c)Arthur Ketels 2008
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -55,13 +55,13 @@ uint8 currentgroup = 0;
|
||||
void redtest(char *ifname, char *ifname2)
|
||||
{
|
||||
int cnt, i, j, oloop, iloop;
|
||||
|
||||
|
||||
printf("Starting Redundant test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
// if (ec_init_redundant(ifname, ifname2))
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config(FALSE, &IOmap) > 0 )
|
||||
@ -69,10 +69,10 @@ void redtest(char *ifname, char *ifname2)
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
|
||||
|
||||
/* configure DC options for every DC capable slave found in the list */
|
||||
ec_configdc();
|
||||
|
||||
|
||||
/* read indevidual slave state and store in ec_slave[] */
|
||||
ec_readstate();
|
||||
for(cnt = 1; cnt <= ec_slavecount ; cnt++)
|
||||
@ -86,7 +86,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
if( !digout && ((ec_slave[cnt].eep_id == 0x0af83052) || (ec_slave[cnt].eep_id == 0x07d83052)))
|
||||
{
|
||||
digout = ec_slave[cnt].outputs;
|
||||
}
|
||||
}
|
||||
}
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
printf("Calculated workcounter %d\n", expectedWKC);
|
||||
@ -122,7 +122,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
for(j = 0 ; j < iloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].inputs + j));
|
||||
}
|
||||
}
|
||||
printf("\r");
|
||||
fflush(stdout);
|
||||
osal_usleep(20000);
|
||||
@ -142,7 +142,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
printf("Request safe operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_SAFE_OP;
|
||||
/* request SAFE_OP state for all slaves */
|
||||
@ -159,25 +159,25 @@ void redtest(char *ifname, char *ifname2)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* add ns to timespec */
|
||||
void add_timespec(struct timespec *ts, int64 addtime)
|
||||
{
|
||||
int64 sec, nsec;
|
||||
|
||||
|
||||
nsec = addtime % NSEC_PER_SEC;
|
||||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_nsec = nsec;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* PI calculation to get linux time synced to DC time */
|
||||
void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
@ -191,7 +191,7 @@ void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
if(delta<0){ integral--; }
|
||||
*offsettime = -(delta / 100) - (integral / 20);
|
||||
gl_delta = delta;
|
||||
}
|
||||
}
|
||||
|
||||
/* RT EtherCAT thread */
|
||||
OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
@ -199,16 +199,16 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
struct timespec ts, tleft;
|
||||
int ht;
|
||||
int64 cycletime;
|
||||
|
||||
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
ht = (ts.tv_nsec / 1000000) + 1; /* round to nearest ms */
|
||||
ts.tv_nsec = ht * 1000000;
|
||||
cycletime = *(int*)ptr * 1000; /* cycletime in ns */
|
||||
toff = 0;
|
||||
dorun = 0;
|
||||
ec_send_processdata();
|
||||
ec_send_processdata();
|
||||
while(1)
|
||||
{
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
add_timespec(&ts, cycletime + toff);
|
||||
/* wait to cycle start */
|
||||
@ -216,19 +216,19 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
if (dorun>0)
|
||||
{
|
||||
wkc = ec_receive_processdata(EC_TIMEOUTRET);
|
||||
|
||||
|
||||
dorun++;
|
||||
/* if we have some digital output, cycle */
|
||||
if( digout ) *digout = (uint8) ((dorun / 16) & 0xff);
|
||||
|
||||
if( digout ) *digout = (uint8) ((dorun / 16) & 0xff);
|
||||
|
||||
if (ec_slave[0].hasdc)
|
||||
{
|
||||
{
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
ec_send_processdata();
|
||||
}
|
||||
}
|
||||
}
|
||||
ec_send_processdata();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
@ -262,16 +262,16 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
ec_writestate(slave);
|
||||
}
|
||||
else if(ec_slave[slave].state > 0)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
@ -279,7 +279,7 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
if (!ec_slave[slave].state)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -290,13 +290,13 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -304,27 +304,27 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
printf("OK : all slaves resumed OPERATIONAL.\n");
|
||||
}
|
||||
osal_usleep(10000);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#define stack64k (64 * 1024)
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
int ctime;
|
||||
|
||||
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nRedundancy test\n");
|
||||
|
||||
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
dorun = 0;
|
||||
ctime = atoi(argv[3]);
|
||||
|
||||
/* create RT thread */
|
||||
osal_thread_create_rt(&thread1, stack64k * 2, &ecatthread, (void*) &ctime);
|
||||
osal_thread_create_rt(&thread1, stack64k * 2, &ecatthread, (void*) &ctime);
|
||||
|
||||
/* create thread to handle slave error handling in OP */
|
||||
osal_thread_create(&thread2, stack64k * 4, &ecatcheck, NULL);
|
||||
osal_thread_create(&thread2, stack64k * 4, &ecatcheck, NULL);
|
||||
|
||||
/* start acyclic part */
|
||||
redtest(argv[1],argv[2]);
|
||||
@ -332,8 +332,8 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
printf("Usage: red_test ifname1 ifname2 cycletime\nifname = eth0 for example\ncycletime in us\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
return (0);
|
||||
|
@ -39,10 +39,10 @@ void simpletest(char *ifname)
|
||||
inOP = FALSE;
|
||||
|
||||
printf("Starting simple test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
|
||||
@ -105,16 +105,16 @@ void simpletest(char *ifname)
|
||||
printf(" %2.2x", *(ec_slave[0].outputs + j));
|
||||
}
|
||||
|
||||
printf(" I:");
|
||||
printf(" I:");
|
||||
for(j = 0 ; j < iloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].inputs + j));
|
||||
}
|
||||
}
|
||||
printf(" T:%lld\r",ec_DCtime);
|
||||
needlf = TRUE;
|
||||
}
|
||||
osal_usleep(5000);
|
||||
|
||||
|
||||
}
|
||||
inOP = FALSE;
|
||||
}
|
||||
@ -130,7 +130,7 @@ void simpletest(char *ifname)
|
||||
i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
printf("\nRequest init state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_INIT;
|
||||
/* request INIT state for all slaves */
|
||||
@ -147,8 +147,8 @@ void simpletest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
{
|
||||
@ -181,16 +181,16 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
ec_writestate(slave);
|
||||
}
|
||||
else if(ec_slave[slave].state > 0)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
@ -198,7 +198,7 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
if (!ec_slave[slave].state)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -209,13 +209,13 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -223,17 +223,17 @@ OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
printf("OK : all slaves resumed OPERATIONAL.\n");
|
||||
}
|
||||
osal_usleep(10000);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
/* create thread to handle slave error handling in OP */
|
||||
// pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);
|
||||
// pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);
|
||||
osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
|
||||
/* start cyclic part */
|
||||
simpletest(argv[1]);
|
||||
@ -241,8 +241,8 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
printf("Usage: simple_test ifname1\nifname = eth0 for example\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
||||
|
@ -108,7 +108,7 @@ char* dtype2string(uint16 dtype)
|
||||
sprintf(hstr, "Type 0x%4.4X", dtype);
|
||||
}
|
||||
return hstr;
|
||||
}
|
||||
}
|
||||
|
||||
char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
{
|
||||
@ -137,50 +137,50 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
{
|
||||
case ECT_BOOLEAN:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
if (*u8) sprintf(hstr, "TRUE");
|
||||
if (*u8) sprintf(hstr, "TRUE");
|
||||
else sprintf(hstr, "FALSE");
|
||||
break;
|
||||
case ECT_INTEGER8:
|
||||
i8 = (int8*) &usdo[0];
|
||||
sprintf(hstr, "0x%2.2x %d", *i8, *i8);
|
||||
sprintf(hstr, "0x%2.2x %d", *i8, *i8);
|
||||
break;
|
||||
case ECT_INTEGER16:
|
||||
i16 = (int16*) &usdo[0];
|
||||
sprintf(hstr, "0x%4.4x %d", *i16, *i16);
|
||||
sprintf(hstr, "0x%4.4x %d", *i16, *i16);
|
||||
break;
|
||||
case ECT_INTEGER32:
|
||||
case ECT_INTEGER24:
|
||||
i32 = (int32*) &usdo[0];
|
||||
sprintf(hstr, "0x%8.8x %d", *i32, *i32);
|
||||
sprintf(hstr, "0x%8.8x %d", *i32, *i32);
|
||||
break;
|
||||
case ECT_INTEGER64:
|
||||
i64 = (int64*) &usdo[0];
|
||||
sprintf(hstr, "0x%16.16llx %lld", *i64, *i64);
|
||||
sprintf(hstr, "0x%16.16llx %lld", *i64, *i64);
|
||||
break;
|
||||
case ECT_UNSIGNED8:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
sprintf(hstr, "0x%2.2x %u", *u8, *u8);
|
||||
sprintf(hstr, "0x%2.2x %u", *u8, *u8);
|
||||
break;
|
||||
case ECT_UNSIGNED16:
|
||||
u16 = (uint16*) &usdo[0];
|
||||
sprintf(hstr, "0x%4.4x %u", *u16, *u16);
|
||||
sprintf(hstr, "0x%4.4x %u", *u16, *u16);
|
||||
break;
|
||||
case ECT_UNSIGNED32:
|
||||
case ECT_UNSIGNED24:
|
||||
u32 = (uint32*) &usdo[0];
|
||||
sprintf(hstr, "0x%8.8x %u", *u32, *u32);
|
||||
sprintf(hstr, "0x%8.8x %u", *u32, *u32);
|
||||
break;
|
||||
case ECT_UNSIGNED64:
|
||||
u64 = (uint64*) &usdo[0];
|
||||
sprintf(hstr, "0x%16.16llx %llu", *u64, *u64);
|
||||
sprintf(hstr, "0x%16.16llx %llu", *u64, *u64);
|
||||
break;
|
||||
case ECT_REAL32:
|
||||
sr = (float*) &usdo[0];
|
||||
sprintf(hstr, "%f", *sr);
|
||||
sprintf(hstr, "%f", *sr);
|
||||
break;
|
||||
case ECT_REAL64:
|
||||
dr = (double*) &usdo[0];
|
||||
sprintf(hstr, "%f", *dr);
|
||||
sprintf(hstr, "%f", *dr);
|
||||
break;
|
||||
case ECT_BIT1:
|
||||
case ECT_BIT2:
|
||||
@ -191,7 +191,7 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
case ECT_BIT7:
|
||||
case ECT_BIT8:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
sprintf(hstr, "0x%x", *u8);
|
||||
sprintf(hstr, "0x%x", *u8);
|
||||
break;
|
||||
case ECT_VISIBLE_STRING:
|
||||
strcpy(hstr, usdo);
|
||||
@ -199,7 +199,7 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
case ECT_OCTET_STRING:
|
||||
hstr[0] = 0x00;
|
||||
for (i = 0 ; i < l ; i++)
|
||||
{
|
||||
{
|
||||
sprintf(es, "0x%2.2x ", usdo[i]);
|
||||
strcat( hstr, es);
|
||||
}
|
||||
@ -321,22 +321,22 @@ int si_map_sdo(int slave)
|
||||
}
|
||||
if(tSM)
|
||||
tSM += SMt_bug_add; // only add if SMt > 0
|
||||
|
||||
|
||||
if (tSM == 3) // outputs
|
||||
{
|
||||
/* read the assign RXPDO */
|
||||
printf(" SM%1d outputs\n addr b index: sub bitl data_type name\n", iSM);
|
||||
Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].outputs - (uint8 *)&IOmap[0]), outputs_bo );
|
||||
outputs_bo += Tsize;
|
||||
}
|
||||
}
|
||||
if (tSM == 4) // inputs
|
||||
{
|
||||
/* read the assign TXPDO */
|
||||
printf(" SM%1d inputs\n addr b index: sub bitl data_type name\n", iSM);
|
||||
Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].inputs - (uint8 *)&IOmap[0]), inputs_bo );
|
||||
inputs_bo += Tsize;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -395,10 +395,10 @@ int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
|
||||
a += 2;
|
||||
c += 2;
|
||||
if (PDO->SyncM[PDO->nPDO] < EC_MAXSM) /* active and in range SM? */
|
||||
{
|
||||
{
|
||||
str_name[0] = 0;
|
||||
if(obj_name)
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
if (t)
|
||||
printf(" SM%1d RXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
|
||||
else
|
||||
@ -442,7 +442,7 @@ int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
|
||||
c += 4 * e;
|
||||
a += 8 * e;
|
||||
c++;
|
||||
}
|
||||
}
|
||||
if (PDO->nPDO >= (EC_MAXEEPDO - 1)) c = PDO->Length; /* limit number of PDO entries in buffer */
|
||||
}
|
||||
while (c < PDO->Length);
|
||||
@ -476,7 +476,7 @@ int si_map_sii(int slave)
|
||||
void si_sdo(int cnt)
|
||||
{
|
||||
int i, j;
|
||||
|
||||
|
||||
ODlist.Entries = 0;
|
||||
memset(&ODlist, 0, sizeof(ODlist));
|
||||
if( ec_readODlist(cnt, &ODlist))
|
||||
@ -484,7 +484,7 @@ void si_sdo(int cnt)
|
||||
printf(" CoE Object Description found, %d entries.\n",ODlist.Entries);
|
||||
for( i = 0 ; i < ODlist.Entries ; i++)
|
||||
{
|
||||
ec_readODdescription(i, &ODlist);
|
||||
ec_readODdescription(i, &ODlist);
|
||||
while(EcatError) printf("%s", ec_elist2string());
|
||||
printf(" Index: %4.4x Datatype: %4.4x Objectcode: %2.2x Name: %s\n",
|
||||
ODlist.Index[i], ODlist.DataType[i], ODlist.ObjectCode[i], ODlist.Name[i]);
|
||||
@ -502,8 +502,8 @@ void si_sdo(int cnt)
|
||||
printf(" Value :%s\n", SDO2string(cnt, ODlist.Index[i], j, OElist.DataType[j]));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -516,12 +516,12 @@ void slaveinfo(char *ifname)
|
||||
int cnt, i, j, nSM;
|
||||
uint16 ssigen;
|
||||
int expectedWKC;
|
||||
|
||||
|
||||
printf("Starting slaveinfo\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config(FALSE, &IOmap) > 0 )
|
||||
@ -529,7 +529,7 @@ void slaveinfo(char *ifname)
|
||||
ec_configdc();
|
||||
while(EcatError) printf("%s", ec_elist2string());
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
printf("Calculated workcounter %d\n", expectedWKC);
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 3);
|
||||
@ -546,8 +546,8 @@ void slaveinfo(char *ifname)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
ec_readstate();
|
||||
for( cnt = 1 ; cnt <= ec_slavecount ; cnt++)
|
||||
{
|
||||
@ -556,8 +556,8 @@ void slaveinfo(char *ifname)
|
||||
ec_slave[cnt].state, ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
|
||||
if (ec_slave[cnt].hasdc) printf(" DCParentport:%d\n", ec_slave[cnt].parentport);
|
||||
printf(" Activeports:%d.%d.%d.%d\n", (ec_slave[cnt].activeports & 0x01) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x02) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x04) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x02) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x04) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x08) > 0 );
|
||||
printf(" Configured address: %4.4x\n", ec_slave[cnt].configadr);
|
||||
printf(" Man: %8.8x ID: %8.8x Rev: %8.8x\n", (int)ec_slave[cnt].eep_man, (int)ec_slave[cnt].eep_id, (int)ec_slave[cnt].eep_rev);
|
||||
@ -588,8 +588,8 @@ void slaveinfo(char *ifname)
|
||||
if((ec_siigetbyte(cnt, ssigen + 0x0d) & 0x02) > 0)
|
||||
{
|
||||
ec_slave[cnt].blockLRW = 1;
|
||||
ec_slave[0].blockLRW++;
|
||||
}
|
||||
ec_slave[0].blockLRW++;
|
||||
}
|
||||
ec_slave[cnt].Ebuscurrent = ec_siigetbyte(cnt, ssigen + 0x0e);
|
||||
ec_slave[cnt].Ebuscurrent += ec_siigetbyte(cnt, ssigen + 0x0f) << 8;
|
||||
ec_slave[0].Ebuscurrent += ec_slave[cnt].Ebuscurrent;
|
||||
@ -606,8 +606,8 @@ void slaveinfo(char *ifname)
|
||||
si_map_sdo(cnt);
|
||||
else
|
||||
si_map_sii(cnt);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -620,8 +620,8 @@ void slaveinfo(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
char ifbuf[1024];
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
* \brief Example code for Simple Open EtherCAT master
|
||||
*
|
||||
* This is a minimal example running rt-kernel TTOS. Check
|
||||
* tutorial files in documentations for som steps to get your
|
||||
* tutorial files in documentations for som steps to get your
|
||||
* system running.
|
||||
* (c)Andreas Karlsson 2012
|
||||
*/
|
||||
@ -142,7 +142,7 @@ uint8 get_input_bit (uint16 slave_no,uint8 module_index)
|
||||
{
|
||||
/* Get the the startbit position in slaves IO byte */
|
||||
uint8 startbit = ec_slave[slave_no].Istartbit;
|
||||
/* Mask bit and return boolean 0 or 1 */
|
||||
/* Mask bit and return boolean 0 or 1 */
|
||||
if (*ec_slave[slave_no].inputs & BIT (module_index - 1 + startbit))
|
||||
return 1;
|
||||
else
|
||||
@ -185,7 +185,7 @@ uint8 get_output_bit (uint16 slave_no,uint8 module_index)
|
||||
{
|
||||
/* Get the the startbit position in slaves IO byte */
|
||||
uint8 startbit = ec_slave[slave_no].Ostartbit;
|
||||
/* Mask bit and return boolean 0 or 1 */
|
||||
/* Mask bit and return boolean 0 or 1 */
|
||||
if (*ec_slave[slave_no].outputs & BIT (module_index - 1 + startbit))
|
||||
return 1;
|
||||
else
|
||||
@ -232,7 +232,7 @@ static void my_cyclic_callback (void * arg)
|
||||
|
||||
void read_io (void * arg)
|
||||
{
|
||||
/* Function connected to cyclic TTOS task
|
||||
/* Function connected to cyclic TTOS task
|
||||
* The function is executed cyclic according
|
||||
* sceduel specified in schedule.tt
|
||||
*/
|
||||
@ -261,7 +261,7 @@ void simpletest(void *arg)
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
rprintp("ec_init succeeded.\n");
|
||||
|
||||
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
{
|
||||
@ -326,7 +326,7 @@ void simpletest(void *arg)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* Simple blinking lamps BOX demo */
|
||||
uint8 digout = 0;
|
||||
|
||||
|
@ -7,7 +7,7 @@
|
||||
*
|
||||
* This test is specifically build for the E/BOX.
|
||||
*
|
||||
* (c)Arthur Ketels 2011
|
||||
* (c)Arthur Ketels 2011
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -39,13 +39,13 @@ typedef struct PACKED
|
||||
int32 ain[2];
|
||||
uint32 tsain;
|
||||
int32 enc[2];
|
||||
} in_EBOXt;
|
||||
} in_EBOXt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
uint8 counter;
|
||||
int16 stream[100];
|
||||
} in_EBOX_streamt;
|
||||
} in_EBOX_streamt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
@ -53,12 +53,12 @@ typedef struct PACKED
|
||||
uint8 dout;
|
||||
int16 aout[2];
|
||||
uint16 pwmout[2];
|
||||
} out_EBOXt;
|
||||
} out_EBOXt;
|
||||
|
||||
typedef struct PACKED
|
||||
{
|
||||
uint8 control;
|
||||
} out_EBOX_streamt;
|
||||
} out_EBOX_streamt;
|
||||
|
||||
// total samples to capture
|
||||
#define MAXSTREAM 200000
|
||||
@ -93,30 +93,30 @@ int16 stream2[MAXSTREAM];
|
||||
int output_cvs(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int i;
|
||||
|
||||
fp = fopen(fname, "w");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
for (i = 0; i < length; i++)
|
||||
{
|
||||
fprintf(fp, "%d %d %d\n", i, stream1[i], stream2[i]);
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
void eboxtest(char *ifname)
|
||||
{
|
||||
int cnt, i;
|
||||
|
||||
|
||||
printf("Starting E/BOX test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
@ -130,9 +130,9 @@ void eboxtest(char *ifname)
|
||||
// reprogram PDO mapping to set slave in stream mode
|
||||
// this can only be done in pre-OP state
|
||||
os=sizeof(ob2); ob2 = 0x1601;
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
os=sizeof(ob2); ob2 = 0x1a01;
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
}
|
||||
|
||||
ec_config_map(&IOmap);
|
||||
@ -141,10 +141,10 @@ void eboxtest(char *ifname)
|
||||
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
|
||||
|
||||
/* configure DC options for every DC capable slave found in the list */
|
||||
printf("DC capable : %d\n",ec_configdc());
|
||||
|
||||
|
||||
/* check configuration */
|
||||
if (( ec_slavecount >= 1 ) &&
|
||||
(strcmp(ec_slave[1].name,"E/BOX") == 0)
|
||||
@ -166,10 +166,10 @@ void eboxtest(char *ifname)
|
||||
}
|
||||
printf("Request operational state for all slaves\n");
|
||||
|
||||
/* send one processdata cycle to init SM in slaves */
|
||||
/* send one processdata cycle to init SM in slaves */
|
||||
ec_send_processdata();
|
||||
ec_receive_processdata(EC_TIMEOUTRET);
|
||||
|
||||
|
||||
ec_slave[0].state = EC_STATE_OPERATIONAL;
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
@ -202,12 +202,12 @@ void eboxtest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("Not all slaves reached operational state.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("E/BOX not found in slave configuration.\n");
|
||||
}
|
||||
}
|
||||
ec_dcsync0(1, FALSE, 8000, 0); // SYNC0 off
|
||||
printf("Request safe operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_SAFE_OP;
|
||||
@ -226,9 +226,9 @@ void eboxtest(char *ifname)
|
||||
// restore PDO to standard mode
|
||||
// this can only be done is pre-op state
|
||||
os=sizeof(ob2); ob2 = 0x1600;
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
os=sizeof(ob2); ob2 = 0x1a00;
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);
|
||||
}
|
||||
printf("Streampos %d\n", streampos);
|
||||
output_cvs("stream.txt", streampos);
|
||||
@ -244,25 +244,25 @@ void eboxtest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* add ns to timespec */
|
||||
void add_timespec(struct timespec *ts, int64 addtime)
|
||||
{
|
||||
int64 sec, nsec;
|
||||
|
||||
|
||||
nsec = addtime % NSEC_PER_SEC;
|
||||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_nsec = nsec;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* PI calculation to get linux time synced to DC time */
|
||||
void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
@ -274,7 +274,7 @@ void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
if(delta>0){ integral++; }
|
||||
if(delta<0){ integral--; }
|
||||
*offsettime = -(delta / 100) - (integral /20);
|
||||
}
|
||||
}
|
||||
|
||||
/* RT EtherCAT thread */
|
||||
void ecatthread( void *ptr )
|
||||
@ -286,7 +286,7 @@ void ecatthread( void *ptr )
|
||||
int i;
|
||||
int pcounter = 0;
|
||||
int64 cycletime;
|
||||
|
||||
|
||||
rc = pthread_mutex_lock(&mutex);
|
||||
rc = gettimeofday(&tp, NULL);
|
||||
|
||||
@ -298,7 +298,7 @@ void ecatthread( void *ptr )
|
||||
toff = 0;
|
||||
dorun = 0;
|
||||
while(1)
|
||||
{
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
add_timespec(&ts, cycletime + toff);
|
||||
/* wait to cycle start */
|
||||
@ -313,7 +313,7 @@ void ecatthread( void *ptr )
|
||||
|
||||
cyclecount++;
|
||||
|
||||
|
||||
|
||||
if((in_EBOX->counter != pcounter) && (streampos < (MAXSTREAM - 1)))
|
||||
{
|
||||
// check if we have timing problems in master
|
||||
@ -336,11 +336,11 @@ void ecatthread( void *ptr )
|
||||
}
|
||||
pcounter = in_EBOX->counter;
|
||||
}
|
||||
|
||||
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
@ -349,9 +349,9 @@ int main(int argc, char *argv[])
|
||||
int ctime;
|
||||
struct sched_param param;
|
||||
int policy = SCHED_OTHER;
|
||||
|
||||
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nE/BOX test\n");
|
||||
|
||||
|
||||
memset(&schedp, 0, sizeof(schedp));
|
||||
/* do not set priority above 49, otherwise sockets are starved */
|
||||
schedp.sched_priority = 30;
|
||||
@ -362,16 +362,16 @@ int main(int argc, char *argv[])
|
||||
usleep(1000);
|
||||
}
|
||||
while (dorun);
|
||||
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
dorun = 1;
|
||||
if( argc > 2)
|
||||
ctime = atoi(argv[2]);
|
||||
else
|
||||
ctime = 1000; // 1ms cycle time
|
||||
/* create RT thread */
|
||||
iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
memset(¶m, 0, sizeof(param));
|
||||
/* give it higher priority */
|
||||
param.sched_priority = 40;
|
||||
@ -383,12 +383,12 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
printf("Usage: ebox ifname [cycletime]\nifname = eth0 for example\ncycletime in us\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
schedp.sched_priority = 0;
|
||||
sched_setscheduler(0, SCHED_OTHER, &schedp);
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
@ -9,7 +9,7 @@
|
||||
* -w write EEPROM, input binary format
|
||||
* -wi write EEPROM, input Intel Hex format
|
||||
*
|
||||
* (c)Arthur Ketels 2010
|
||||
* (c)Arthur Ketels 2010
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -52,30 +52,30 @@ char sline[MAXSLENGTH];
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (cc < MAXBUF))
|
||||
ebuf[cc++] = (uint8)c;
|
||||
*length = cc;
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int input_intelhex(char *fname, int *start, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int c, sc, retval = 1;
|
||||
int ll, ladr, lt, sn, i, lval;
|
||||
int hstart, hlength, sum;
|
||||
|
||||
fp = fopen(fname, "r");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
hstart = MAXBUF;
|
||||
hlength = 0;
|
||||
@ -116,7 +116,7 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
printf("Invalid checksum.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
while (c != EOF);
|
||||
if (retval)
|
||||
@ -125,34 +125,34 @@ int input_intelhex(char *fname, int *start, int *length)
|
||||
*start = hstart;
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
int output_bin(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc;
|
||||
|
||||
fp = fopen(fname, "wb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
for (cc = 0 ; cc < length ; cc++)
|
||||
fputc( ebuf[cc], fp);
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int output_intelhex(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, ll, sum, i;
|
||||
|
||||
fp = fopen(fname, "w");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (cc < length)
|
||||
{
|
||||
@ -168,9 +168,9 @@ int output_intelhex(char *fname, int length)
|
||||
fprintf(fp, "%2.2X\n", (0x100 - sum) & 0xff);
|
||||
cc += ll;
|
||||
}
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fclose(fp);
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -181,7 +181,7 @@ int eeprom_read(int slave, int start, int length)
|
||||
uint32 b4;
|
||||
uint64 b8;
|
||||
uint8 eepctl;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -221,10 +221,10 @@ int eeprom_read(int slave, int start, int length)
|
||||
ebuf[i+3] = (uint8) (b4 >> 24);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -234,7 +234,7 @@ int eeprom_write(int slave, int start, int length)
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
|
||||
if((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
@ -255,10 +255,10 @@ int eeprom_write(int slave, int start, int length)
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -266,10 +266,10 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
{
|
||||
int w, rc = 0, estart, esize;
|
||||
uint16 *wbuf;
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
|
||||
w = 0x0000;
|
||||
@ -319,7 +319,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
if (mode == MODE_WRITEBIN) rc = input_bin(fname, &esize);
|
||||
|
||||
if (rc > 0)
|
||||
{
|
||||
{
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
printf("Slave %d\n", slave);
|
||||
printf(" Vendor ID : %8.8X\n",*(uint32 *)(wbuf + 0x08));
|
||||
@ -337,7 +337,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
printf("\nTotal EEPROM write time :%ldms\n", (tdif.usec+(tdif.sec*1000000L)) / 1000);
|
||||
}
|
||||
else
|
||||
printf("Error reading file, abort.\n");
|
||||
printf("Error reading file, abort.\n");
|
||||
}
|
||||
}
|
||||
else
|
||||
@ -351,22 +351,22 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
}
|
||||
else
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
ec_adaptert * adapter = NULL;
|
||||
ec_adaptert * adapter = NULL;
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nEEPROM tool\n");
|
||||
|
||||
if (argc > 4)
|
||||
{
|
||||
{
|
||||
slave = atoi(argv[2]);
|
||||
mode = MODE_NONE;
|
||||
if ((strncmp(argv[3], "-r", sizeof("-r")) == 0)) mode = MODE_READBIN;
|
||||
if ((strncmp(argv[3], "-ri", sizeof("-ri")) == 0)) mode = MODE_READINTEL;
|
||||
if ((strncmp(argv[3], "-w", sizeof("-w")) == 0)) mode = MODE_WRITEBIN;
|
||||
if ((strncmp(argv[3], "-wi", sizeof("-wi")) == 0)) mode = MODE_WRITEINTEL;
|
||||
|
||||
|
||||
/* start tool */
|
||||
eepromtool(argv[1],slave,mode,argv[4]);
|
||||
}
|
||||
@ -387,9 +387,9 @@ int main(int argc, char *argv[])
|
||||
printf ("Description : %s, Device to use for wpcap: %s\n", adapter->desc,adapter->name);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
|
||||
|
||||
return (0);
|
||||
}
|
||||
|
@ -41,11 +41,11 @@ uint16 argslave;
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
if(fp == NULL)
|
||||
if(fp == NULL)
|
||||
return 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (cc < FWBUFSIZE))
|
||||
filebuffer[cc++] = (uint8)c;
|
||||
@ -56,12 +56,12 @@ int input_bin(char *fname, int *length)
|
||||
|
||||
|
||||
void boottest(char *ifname, uint16 slave, char *filename)
|
||||
{
|
||||
{
|
||||
printf("Starting firmware update example\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
|
||||
@ -69,7 +69,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
{
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
|
||||
|
||||
printf("Request init state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_INIT;
|
||||
ec_writestate(slave);
|
||||
@ -104,7 +104,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
|
||||
/* program SM1 mailbox out for slave */
|
||||
ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM1, sizeof(ec_smt), &ec_slave[slave].SM[1], EC_TIMEOUTRET);
|
||||
|
||||
|
||||
printf("Request BOOT state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_BOOT;
|
||||
ec_writestate(slave);
|
||||
@ -140,15 +140,15 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nFirmware update example\n");
|
||||
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
argslave = atoi(argv[2]);
|
||||
boottest(argv[1], argslave, argv[3]);
|
||||
}
|
||||
@ -159,8 +159,8 @@ int main(int argc, char *argv[])
|
||||
printf("slave = slave number in EtherCAT order 1..n\n");
|
||||
printf("fname = binary file to store in slave\n");
|
||||
printf("CAUTION! Using the wrong file can result in a bricked slave!\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
||||
|
@ -7,7 +7,7 @@
|
||||
*
|
||||
* This is a redundancy test.
|
||||
*
|
||||
* (c)Arthur Ketels 2008
|
||||
* (c)Arthur Ketels 2008
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
@ -50,12 +50,12 @@ int wcounter;
|
||||
void redtest(char *ifname, char *ifname2)
|
||||
{
|
||||
int cnt, i, j, oloop, iloop;
|
||||
|
||||
|
||||
printf("Starting Redundant test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init_redundant(ifname, ifname2))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config(FALSE, &IOmap) > 0 )
|
||||
@ -63,10 +63,10 @@ void redtest(char *ifname, char *ifname2)
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
|
||||
|
||||
/* configure DC options for every DC capable slave found in the list */
|
||||
ec_configdc();
|
||||
|
||||
|
||||
/* read indevidual slave state and store in ec_slave[] */
|
||||
ec_readstate();
|
||||
for(cnt = 1; cnt <= ec_slavecount ; cnt++)
|
||||
@ -80,7 +80,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
if( !digout && ((ec_slave[cnt].eep_id == 0x07d43052) || (ec_slave[cnt].eep_id == 0x07d83052)))
|
||||
{
|
||||
digout = ec_slave[cnt].outputs;
|
||||
}
|
||||
}
|
||||
}
|
||||
printf("Request operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_OPERATIONAL;
|
||||
@ -110,7 +110,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
for(j = 0 ; j < iloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].inputs + j));
|
||||
}
|
||||
}
|
||||
printf("\n");
|
||||
usleep(20000);
|
||||
}
|
||||
@ -119,7 +119,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
else
|
||||
{
|
||||
printf("Not all slaves reached operational state.\n");
|
||||
}
|
||||
}
|
||||
printf("Request safe operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_SAFE_OP;
|
||||
/* request SAFE_OP state for all slaves */
|
||||
@ -136,25 +136,25 @@ void redtest(char *ifname, char *ifname2)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* add ns to timespec */
|
||||
void add_timespec(struct timespec *ts, int64 addtime)
|
||||
{
|
||||
int64 sec, nsec;
|
||||
|
||||
|
||||
nsec = addtime % NSEC_PER_SEC;
|
||||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_nsec = nsec;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* PI calculation to get linux time synced to DC time */
|
||||
void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
@ -167,7 +167,7 @@ void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
|
||||
if(delta>0){ integral++; }
|
||||
if(delta<0){ integral--; }
|
||||
*offsettime = -(delta / 100) - (integral / 20);
|
||||
}
|
||||
}
|
||||
|
||||
/* RT EtherCAT thread */
|
||||
void ecatthread( void *ptr )
|
||||
@ -177,7 +177,7 @@ void ecatthread( void *ptr )
|
||||
int rc;
|
||||
int ht;
|
||||
int64 cycletime;
|
||||
|
||||
|
||||
rc = pthread_mutex_lock(&mutex);
|
||||
rc = gettimeofday(&tp, NULL);
|
||||
|
||||
@ -189,7 +189,7 @@ void ecatthread( void *ptr )
|
||||
toff = 0;
|
||||
dorun = 0;
|
||||
while(1)
|
||||
{
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
add_timespec(&ts, cycletime + toff);
|
||||
/* wait to cycle start */
|
||||
@ -199,20 +199,20 @@ void ecatthread( void *ptr )
|
||||
rc = gettimeofday(&tp, NULL);
|
||||
|
||||
ec_send_processdata();
|
||||
|
||||
|
||||
wcounter = ec_receive_processdata(EC_TIMEOUTRET);
|
||||
|
||||
|
||||
dorun++;
|
||||
/* if we have some digital output, cycle */
|
||||
if( digout ) *digout = (uint8) ((dorun / 16) & 0xff);
|
||||
|
||||
if( digout ) *digout = (uint8) ((dorun / 16) & 0xff);
|
||||
|
||||
if (ec_slave[0].hasdc)
|
||||
{
|
||||
{
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
@ -221,9 +221,9 @@ int main(int argc, char *argv[])
|
||||
int ctime;
|
||||
struct sched_param param;
|
||||
int policy = SCHED_OTHER;
|
||||
|
||||
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nRedundancy test\n");
|
||||
|
||||
|
||||
memset(&schedp, 0, sizeof(schedp));
|
||||
/* do not set priority above 49, otherwise sockets are starved */
|
||||
schedp.sched_priority = 30;
|
||||
@ -234,13 +234,13 @@ int main(int argc, char *argv[])
|
||||
usleep(1000);
|
||||
}
|
||||
while (dorun);
|
||||
|
||||
|
||||
if (argc > 3)
|
||||
{
|
||||
{
|
||||
dorun = 1;
|
||||
ctime = atoi(argv[3]);
|
||||
/* create RT thread */
|
||||
iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);
|
||||
memset(¶m, 0, sizeof(param));
|
||||
/* give it higher priority */
|
||||
param.sched_priority = 40;
|
||||
@ -252,8 +252,8 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
printf("Usage: red_test ifname1 ifname2 cycletime\nifname = eth0 for example\ncycletime in us\n");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
schedp.sched_priority = 0;
|
||||
sched_setscheduler(0, SCHED_OTHER, &schedp);
|
||||
|
||||
|
@ -59,7 +59,7 @@ int EL7031setup(uint16 slave)
|
||||
|
||||
// Set PDO mapping using Complete Access
|
||||
// Strange, writing CA works, reading CA doesn't
|
||||
// This is a protocol error of the slave.
|
||||
// This is a protocol error of the slave.
|
||||
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);
|
||||
|
||||
@ -130,10 +130,10 @@ void simpletest(char *ifname)
|
||||
inOP = FALSE;
|
||||
|
||||
printf("Starting simple test\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
|
||||
@ -207,7 +207,7 @@ void simpletest(char *ifname)
|
||||
wkc_count = 0;
|
||||
inOP = TRUE;
|
||||
|
||||
|
||||
|
||||
/* cyclic loop, reads data from RT thread */
|
||||
for(i = 1; i <= 500; i++)
|
||||
{
|
||||
@ -220,16 +220,16 @@ void simpletest(char *ifname)
|
||||
printf(" %2.2x", *(ec_slave[0].outputs + j));
|
||||
}
|
||||
|
||||
printf(" I:");
|
||||
printf(" I:");
|
||||
for(j = 0 ; j < iloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].inputs + j));
|
||||
}
|
||||
}
|
||||
printf(" T:%lld\r",ec_DCtime);
|
||||
needlf = TRUE;
|
||||
}
|
||||
osal_usleep(50000);
|
||||
|
||||
|
||||
}
|
||||
inOP = FALSE;
|
||||
}
|
||||
@ -245,7 +245,7 @@ void simpletest(char *ifname)
|
||||
i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* stop RT thread */
|
||||
timeKillEvent(mmResult);
|
||||
@ -266,11 +266,11 @@ void simpletest(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//DWORD WINAPI ecatcheck( LPVOID lpParam )
|
||||
OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
//DWORD WINAPI ecatcheck( LPVOID lpParam )
|
||||
OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
{
|
||||
int slave;
|
||||
|
||||
@ -301,16 +301,16 @@ OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
ec_writestate(slave);
|
||||
}
|
||||
else if(ec_slave[slave].state > 0)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
@ -318,7 +318,7 @@ OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
if (!ec_slave[slave].state)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -329,13 +329,13 @@ OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -343,20 +343,20 @@ OSAL_THREAD_FUNC ecatcheck(void *lpParam)
|
||||
printf("OK : all slaves resumed OPERATIONAL.\n");
|
||||
}
|
||||
osal_usleep(10000);
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
char ifbuf[1024];
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
ec_adaptert * adapter = NULL;
|
||||
ec_adaptert * adapter = NULL;
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
/* create thread to handle slave error handling in OP */
|
||||
osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
|
||||
strcpy(ifbuf, argv[1]);
|
||||
@ -374,8 +374,8 @@ int main(int argc, char *argv[])
|
||||
printf ("Description : %s, Device to use for wpcap: %s\n", adapter->desc,adapter->name);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
||||
|
@ -108,7 +108,7 @@ char* dtype2string(uint16 dtype)
|
||||
sprintf(hstr, "Type 0x%4.4X", dtype);
|
||||
}
|
||||
return hstr;
|
||||
}
|
||||
}
|
||||
|
||||
char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
{
|
||||
@ -137,50 +137,50 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
{
|
||||
case ECT_BOOLEAN:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
if (*u8) sprintf(hstr, "TRUE");
|
||||
if (*u8) sprintf(hstr, "TRUE");
|
||||
else sprintf(hstr, "FALSE");
|
||||
break;
|
||||
case ECT_INTEGER8:
|
||||
i8 = (int8*) &usdo[0];
|
||||
sprintf(hstr, "0x%2.2x %d", *i8, *i8);
|
||||
sprintf(hstr, "0x%2.2x %d", *i8, *i8);
|
||||
break;
|
||||
case ECT_INTEGER16:
|
||||
i16 = (int16*) &usdo[0];
|
||||
sprintf(hstr, "0x%4.4x %d", *i16, *i16);
|
||||
sprintf(hstr, "0x%4.4x %d", *i16, *i16);
|
||||
break;
|
||||
case ECT_INTEGER32:
|
||||
case ECT_INTEGER24:
|
||||
i32 = (int32*) &usdo[0];
|
||||
sprintf(hstr, "0x%8.8x %d", *i32, *i32);
|
||||
sprintf(hstr, "0x%8.8x %d", *i32, *i32);
|
||||
break;
|
||||
case ECT_INTEGER64:
|
||||
i64 = (int64*) &usdo[0];
|
||||
sprintf(hstr, "0x%16.16llx %lld", *i64, *i64);
|
||||
sprintf(hstr, "0x%16.16llx %lld", *i64, *i64);
|
||||
break;
|
||||
case ECT_UNSIGNED8:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
sprintf(hstr, "0x%2.2x %u", *u8, *u8);
|
||||
sprintf(hstr, "0x%2.2x %u", *u8, *u8);
|
||||
break;
|
||||
case ECT_UNSIGNED16:
|
||||
u16 = (uint16*) &usdo[0];
|
||||
sprintf(hstr, "0x%4.4x %u", *u16, *u16);
|
||||
sprintf(hstr, "0x%4.4x %u", *u16, *u16);
|
||||
break;
|
||||
case ECT_UNSIGNED32:
|
||||
case ECT_UNSIGNED24:
|
||||
u32 = (uint32*) &usdo[0];
|
||||
sprintf(hstr, "0x%8.8x %u", *u32, *u32);
|
||||
sprintf(hstr, "0x%8.8x %u", *u32, *u32);
|
||||
break;
|
||||
case ECT_UNSIGNED64:
|
||||
u64 = (uint64*) &usdo[0];
|
||||
sprintf(hstr, "0x%16.16llx %llu", *u64, *u64);
|
||||
sprintf(hstr, "0x%16.16llx %llu", *u64, *u64);
|
||||
break;
|
||||
case ECT_REAL32:
|
||||
sr = (float*) &usdo[0];
|
||||
sprintf(hstr, "%f", *sr);
|
||||
sprintf(hstr, "%f", *sr);
|
||||
break;
|
||||
case ECT_REAL64:
|
||||
dr = (double*) &usdo[0];
|
||||
sprintf(hstr, "%f", *dr);
|
||||
sprintf(hstr, "%f", *dr);
|
||||
break;
|
||||
case ECT_BIT1:
|
||||
case ECT_BIT2:
|
||||
@ -191,7 +191,7 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
case ECT_BIT7:
|
||||
case ECT_BIT8:
|
||||
u8 = (uint8*) &usdo[0];
|
||||
sprintf(hstr, "0x%x", *u8);
|
||||
sprintf(hstr, "0x%x", *u8);
|
||||
break;
|
||||
case ECT_VISIBLE_STRING:
|
||||
strcpy(hstr, usdo);
|
||||
@ -199,7 +199,7 @@ char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
|
||||
case ECT_OCTET_STRING:
|
||||
hstr[0] = 0x00;
|
||||
for (i = 0 ; i < l ; i++)
|
||||
{
|
||||
{
|
||||
sprintf(es, "0x%2.2x ", usdo[i]);
|
||||
strcat( hstr, es);
|
||||
}
|
||||
@ -321,22 +321,22 @@ int si_map_sdo(int slave)
|
||||
}
|
||||
if(tSM)
|
||||
tSM += SMt_bug_add; // only add if SMt > 0
|
||||
|
||||
|
||||
if (tSM == 3) // outputs
|
||||
{
|
||||
/* read the assign RXPDO */
|
||||
printf(" SM%1d outputs\n addr b index: sub bitl data_type name\n", iSM);
|
||||
Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].outputs - (uint8 *)&IOmap[0]), outputs_bo );
|
||||
outputs_bo += Tsize;
|
||||
}
|
||||
}
|
||||
if (tSM == 4) // inputs
|
||||
{
|
||||
/* read the assign TXPDO */
|
||||
printf(" SM%1d inputs\n addr b index: sub bitl data_type name\n", iSM);
|
||||
Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].inputs - (uint8 *)&IOmap[0]), inputs_bo );
|
||||
inputs_bo += Tsize;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -395,10 +395,10 @@ int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
|
||||
a += 2;
|
||||
c += 2;
|
||||
if (PDO->SyncM[PDO->nPDO] < EC_MAXSM) /* active and in range SM? */
|
||||
{
|
||||
{
|
||||
str_name[0] = 0;
|
||||
if(obj_name)
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
if (t)
|
||||
printf(" SM%1d RXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
|
||||
else
|
||||
@ -422,7 +422,7 @@ int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
|
||||
|
||||
str_name[0] = 0;
|
||||
if(obj_name)
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
ec_siistring(str_name, slave, obj_name);
|
||||
|
||||
printf(" [0x%4.4X.%1d] 0x%4.4X:0x%2.2X 0x%2.2X", abs_offset, abs_bit, obj_idx, obj_subidx, bitlen);
|
||||
printf(" %-12s %s\n", dtype2string(obj_datatype), str_name);
|
||||
@ -438,7 +438,7 @@ int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
|
||||
c += 4 * e;
|
||||
a += 8 * e;
|
||||
c++;
|
||||
}
|
||||
}
|
||||
if (PDO->nPDO >= (EC_MAXEEPDO - 1)) c = PDO->Length; /* limit number of PDO entries in buffer */
|
||||
}
|
||||
while (c < PDO->Length);
|
||||
@ -472,7 +472,7 @@ int si_map_sii(int slave)
|
||||
void si_sdo(int cnt)
|
||||
{
|
||||
int i, j;
|
||||
|
||||
|
||||
ODlist.Entries = 0;
|
||||
memset(&ODlist, 0, sizeof(ODlist));
|
||||
if( ec_readODlist(cnt, &ODlist))
|
||||
@ -480,7 +480,7 @@ void si_sdo(int cnt)
|
||||
printf(" CoE Object Description found, %d entries.\n",ODlist.Entries);
|
||||
for( i = 0 ; i < ODlist.Entries ; i++)
|
||||
{
|
||||
ec_readODdescription(i, &ODlist);
|
||||
ec_readODdescription(i, &ODlist);
|
||||
while(EcatError) printf("%s", ec_elist2string());
|
||||
printf(" Index: %4.4x Datatype: %4.4x Objectcode: %2.2x Name: %s\n",
|
||||
ODlist.Index[i], ODlist.DataType[i], ODlist.ObjectCode[i], ODlist.Name[i]);
|
||||
@ -498,8 +498,8 @@ void si_sdo(int cnt)
|
||||
printf(" Value :%s\n", SDO2string(cnt, ODlist.Index[i], j, OElist.DataType[j]));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -512,12 +512,12 @@ void slaveinfo(char *ifname)
|
||||
int cnt, i, j, nSM;
|
||||
uint16 ssigen;
|
||||
int expectedWKC;
|
||||
|
||||
|
||||
printf("Starting slaveinfo\n");
|
||||
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config(FALSE, &IOmap) > 0 )
|
||||
@ -525,7 +525,7 @@ void slaveinfo(char *ifname)
|
||||
ec_configdc();
|
||||
while(EcatError) printf("%s", ec_elist2string());
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
printf("Calculated workcounter %d\n", expectedWKC);
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 3);
|
||||
@ -542,8 +542,8 @@ void slaveinfo(char *ifname)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
ec_readstate();
|
||||
for( cnt = 1 ; cnt <= ec_slavecount ; cnt++)
|
||||
{
|
||||
@ -552,8 +552,8 @@ void slaveinfo(char *ifname)
|
||||
ec_slave[cnt].state, ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
|
||||
if (ec_slave[cnt].hasdc) printf(" DCParentport:%d\n", ec_slave[cnt].parentport);
|
||||
printf(" Activeports:%d.%d.%d.%d\n", (ec_slave[cnt].activeports & 0x01) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x02) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x04) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x02) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x04) > 0 ,
|
||||
(ec_slave[cnt].activeports & 0x08) > 0 );
|
||||
printf(" Configured address: %4.4x\n", ec_slave[cnt].configadr);
|
||||
printf(" Man: %8.8x ID: %8.8x Rev: %8.8x\n", (int)ec_slave[cnt].eep_man, (int)ec_slave[cnt].eep_id, (int)ec_slave[cnt].eep_rev);
|
||||
@ -584,8 +584,8 @@ void slaveinfo(char *ifname)
|
||||
if((ec_siigetbyte(cnt, ssigen + 0x0d) & 0x02) > 0)
|
||||
{
|
||||
ec_slave[cnt].blockLRW = 1;
|
||||
ec_slave[0].blockLRW++;
|
||||
}
|
||||
ec_slave[0].blockLRW++;
|
||||
}
|
||||
ec_slave[cnt].Ebuscurrent = ec_siigetbyte(cnt, ssigen + 0x0e);
|
||||
ec_slave[cnt].Ebuscurrent += ec_siigetbyte(cnt, ssigen + 0x0f) << 8;
|
||||
ec_slave[0].Ebuscurrent += ec_slave[cnt].Ebuscurrent;
|
||||
@ -602,8 +602,8 @@ void slaveinfo(char *ifname)
|
||||
si_map_sdo(cnt);
|
||||
else
|
||||
si_map_sii(cnt);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -616,8 +616,8 @@ void slaveinfo(char *ifname)
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
char ifbuf[1024];
|
||||
|
||||
@ -625,9 +625,9 @@ int main(int argc, char *argv[])
|
||||
{
|
||||
ec_adaptert * adapter = NULL;
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nSlaveinfo\n");
|
||||
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
{
|
||||
if ((argc > 2) && (strncmp(argv[2], "-sdo", sizeof("-sdo")) == 0)) printSDO = TRUE;
|
||||
if ((argc > 2) && (strncmp(argv[2], "-map", sizeof("-map")) == 0)) printMAP = TRUE;
|
||||
/* start slaveinfo */
|
||||
@ -645,8 +645,8 @@ int main(int argc, char *argv[])
|
||||
printf ("Description : %s, Device to use for wpcap: %s\n", adapter->desc,adapter->name);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user