pull/289/merge
thepyper 2019-05-15 07:26:17 +00:00 committed by GitHub
commit 268b736443
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
25 changed files with 2064 additions and 4 deletions

3
.gitmodules vendored 100644
View File

@ -0,0 +1,3 @@
[submodule "libs/circle-stdlib"]
path = libs/circle-stdlib
url = https://github.com/smuehlst/circle-stdlib.git

View File

@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.8.4)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/Modules")
project(SOEM C)
project(SOEM C CXX)
if (CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT)
# Default to installing in SOEM source directory
@ -48,13 +48,23 @@ elseif(${CMAKE_SYSTEM_NAME} MATCHES "rtems")
set(OS "rtems")
set(SOEM_LIB_INSTALL_DIR ${LIB_DIR})
set(BUILD_TESTS FALSE)
elseif(${CMAKE_SYSTEM_NAME} MATCHES "circle")
set(OS "circle")
set(CMAKE_C_COMPILER arm-none-eabi-gcc)
set(CMAKE_CXX_COMPILER arm-none-eabi-g++)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DAARCH=32 -march=armv8-a -mtune=cortex-a53 -marm -mfpu=neon-fp-armv8 -mfloat-abi=hard")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DAARCH=32 -march=armv8-a -mtune=cortex-a53 -marm -mfpu=neon-fp-armv8 -mfloat-abi=hard")
include_directories(./libs/circle-stdlib/libs/circle/include)
include_directories(./libs/circle-stdlib/libs/circle-newlib/include)
include_directories(./libs/circle-stdlib/libs/circle-newlib/newlib/libc/include)
include_directories(./libs/circle-stdlib/libs/circle-newlib/newlib/libm/include)
endif()
message("OS is ${OS}")
file(GLOB SOEM_SOURCES soem/*.c)
file(GLOB OSAL_SOURCES osal/${OS}/*.c)
file(GLOB OSHW_SOURCES oshw/${OS}/*.c)
file(GLOB OSAL_SOURCES osal/${OS}/*.c osal/${OS}/*.cpp)
file(GLOB OSHW_SOURCES oshw/${OS}/*.c oshw/${OS}/*.cpp)
file(GLOB SOEM_HEADERS soem/*.h)
file(GLOB OSAL_HEADERS osal/osal.h osal/${OS}/*.h)
@ -81,7 +91,9 @@ install(FILES
${OSHW_HEADERS}
DESTINATION ${SOEM_INCLUDE_INSTALL_DIR})
if(BUILD_TESTS)
if(${OS} MATCHES "circle")
elseif(BUILD_TESTS)
add_subdirectory(test/linux/slaveinfo)
add_subdirectory(test/linux/eepromtool)
add_subdirectory(test/linux/simple_test)

26
build_rpi_3.sh 100644
View File

@ -0,0 +1,26 @@
#execute in a MSYS2-MINGW32 shell, with arm-none-eabi-gcc already in path.
#export PATH=$PATH:/h/Qt/gcc-arm-none-eabi-8-2018-q4-major-win32/bin
if [ "$1" == "" ]; then
#/h/Qt/gcc-arm-none-eabi-8-2018-q4-major-win32/lib/gcc/arm-none-eabi/8.2.1/include
echo "Usage: build_rpi_3.sh <path to stddef.h>"
exit
fi
export HOMEDIR=$PWD
cd $HOMEDIR/libs/circle-stdlib
./configure -r 3 -s $1
make
cd $HOMEDIR
mkdir build
cd build
cmake -D CMAKE_SYSTEM_NAME=circle ../
make

@ -0,0 +1 @@
Subproject commit dda16112cdb5470240cd51fb33bf72b311634340

View File

@ -0,0 +1,137 @@
#include "cethercatmaster.h"
#include <circle/sched/scheduler.h>
#include <circle/synchronize.h>
#include <circle/timer.h>
#include <circle/types.h>
#include <circle/alloc.h>
#include <assert.h>
#include <osal.h>
#include <time.h>
CEtherCATMaster *_instance = 0L;
CEtherCATMaster::CEtherCATMaster(bool use_scheduler)
: _use_scheduler(use_scheduler)
{
// Cannot create more than one instance
assert(_instance == 0L);
_instance = this;
}
bool CEtherCATMaster::IsSchedulerFriendly() const
{
return _use_scheduler;
}
bool CEtherCATMaster::IsActive()
{
return (_instance != 0L);
}
CEtherCATMaster *CEtherCATMaster::Get()
{
assert(_instance != 0L);
return _instance;
}
int osal_usleep(uint32 usec)
{
if (!CScheduler::IsActive()) {
// Busy-waiting sleep
CTimer::SimpleusDelay(usec);
} else if (!CEtherCATMaster::IsActive()) {
// Busy-waiting sleep
CTimer::SimpleusDelay(usec);
} else if (!CEtherCATMaster::Get()->IsSchedulerFriendly()) {
// Busy-waiting sleep
CTimer::SimpleusDelay(usec);
} else {
// Scheduler-friendly sleep
CScheduler::Get()->usSleep(usec);
}
return 0;
}
static long long get_monotonic_clock()
{
// Copied from circle's timer, using both words to get 64bit monotonic clock
InstructionSyncBarrier();
u32 nCNTPCTLow, nCNTPCTHigh;
asm volatile ("mrrc p15, 0, %0, %1, c14" : "=r" (nCNTPCTLow), "=r" (nCNTPCTHigh));
return (((long long)nCNTPCTHigh) << 32) | nCNTPCTLow;
}
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
{
long long usec = get_monotonic_clock();
tv->tv_sec = usec / 1000000LL;
tv->tv_usec = usec % 1000000LL;
return 0;
}
ec_timet osal_current_time(void)
{
struct timeval current_time;
ec_timet return_value;
osal_gettimeofday(&current_time, 0);
return_value.sec = current_time.tv_sec;
return_value.usec = current_time.tv_usec;
return return_value;
}
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
{
if (end->usec < start->usec) {
diff->sec = end->sec - start->sec - 1;
diff->usec = end->usec + 1000000 - start->usec;
} else {
diff->sec = end->sec - start->sec;
diff->usec = end->usec - start->usec;
}
}
void osal_timer_start(osal_timert * self, uint32 timeout_usec)
{
long long stop_time_usec = get_monotonic_clock() + (long long)timeout_usec;
self->stop_time.sec = stop_time_usec / 1000000LL;
self->stop_time.usec = stop_time_usec % 1000000LL;
}
boolean osal_timer_is_expired(osal_timert * self)
{
long long now_usec = get_monotonic_clock();
long long stop_time_usec = self->stop_time.sec * 1000000LL + self->stop_time.usec;
return (now_usec >= stop_time_usec);
}
void *osal_malloc(size_t size)
{
// Use circle's malloc
return malloc(size);
}
void osal_free(void *ptr)
{
// Use circle's free
free(ptr);
}
int osal_thread_create(void *thandle, int stacksize, void *func, void *param)
{
// Not supported
return 0;
}
int osal_thread_create_rt(void *thandle, int stacksize, void *func, void *param)
{
// Not supported
return 0;
}

View File

@ -0,0 +1,19 @@
#ifndef CETHERCATMASTER_H
#define CETHERCATMASTER_H
class CEtherCATMaster
{
public:
CEtherCATMaster(bool use_scheduler);
bool IsSchedulerFriendly() const;
static bool IsActive();
static CEtherCATMaster* Get();
private:
bool _use_scheduler;
};
#endif // CETHERCATMASTER_H

View File

@ -0,0 +1,102 @@
#include <circle/sched/scheduler.h>
#include <circle/synchronize.h>
#include <circle/timer.h>
#include <circle/types.h>
#include <circle/alloc.h>
#include <assert.h>
#include <osal.h>
#include <time.h>
int osal_usleep(uint32 usec)
{
if (CScheduler::IsActive()) {
// Scheduler-friendly sleep
CScheduler::Get()->usSleep(usec);
} else {
// Busy-waiting sleep
CTimer::SimpleusDelay(usec);
}
return 0;
}
static long long get_monotonic_clock()
{
// Copied from circle's timer, using both words to get 64bit monotonic clock
InstructionSyncBarrier();
u32 nCNTPCTLow, nCNTPCTHigh;
asm volatile ("mrrc p15, 0, %0, %1, c14" : "=r" (nCNTPCTLow), "=r" (nCNTPCTHigh));
return (((long long)nCNTPCTHigh) << 32) | nCNTPCTLow;
}
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
{
long long usec = get_monotonic_clock();
tv->tv_sec = usec / 1000000LL;
tv->tv_usec = usec % 1000000LL;
return 0;
}
ec_timet osal_current_time(void)
{
struct timeval current_time;
ec_timet return_value;
osal_gettimeofday(&current_time, 0);
return_value.sec = current_time.tv_sec;
return_value.usec = current_time.tv_usec;
return return_value;
}
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
{
if (end->usec < start->usec) {
diff->sec = end->sec - start->sec - 1;
diff->usec = end->usec + 1000000 - start->usec;
} else {
diff->sec = end->sec - start->sec;
diff->usec = end->usec - start->usec;
}
}
void osal_timer_start(osal_timert * self, uint32 timeout_usec)
{
long long stop_time_usec = get_monotonic_clock() + (long long)timeout_usec;
self->stop_time.sec = stop_time_usec / 1000000LL;
self->stop_time.usec = stop_time_usec % 1000000LL;
}
boolean osal_timer_is_expired(osal_timert * self)
{
long long now_usec = get_monotonic_clock();
long long stop_time_usec = self->stop_time.sec * 1000000LL + self->stop_time.usec;
return (now_usec >= stop_time_usec);
}
void *osal_malloc(size_t size)
{
// Use circle's malloc
return malloc(size);
}
void osal_free(void *ptr)
{
// Use circle's free
free(ptr);
}
int osal_thread_create(void *thandle, int stacksize, void *func, void *param)
{
// Not supported
return 0;
}
int osal_thread_create_rt(void *thandle, int stacksize, void *func, void *param)
{
// Not supported
return 0;
}

View File

@ -0,0 +1,44 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#ifndef _osal_defs_
#define _osal_defs_
#include <circle/types.h>
#include <circle/macros.h>
#define _osal_defs_circle_
#ifdef __cplusplus
extern "C"
{
#endif
// define if debug printf is needed
//#define EC_DEBUG
#ifdef EC_DEBUG
#define EC_PRINT printf
#else
#define EC_PRINT(...) do {} while (0)
#endif
#ifndef PACKED_BEGIN
#define PACKED_BEGIN
#endif
#ifndef PACKED_END
#define PACKED_END
#endif
#define OSAL_THREAD_HANDLE void *
#define OSAL_THREAD_FUNC void
#define OSAL_THREAD_FUNC_RT void
#ifdef __cplusplus
}
#endif
#endif

View File

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

View File

@ -0,0 +1,579 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* EtherCAT RAW socket driver.
*
* Low level interface functions to send and receive EtherCAT packets.
* EtherCAT has the property that packets are only send by the master,
* and the send packets always return in the receive buffer.
* There can be multiple packets "on the wire" before they return.
* To combine the received packets with the original send packets a buffer
* system is installed. The identifier is put in the index item of the
* EtherCAT header. The index is stored and compared when a frame is received.
* If there is a match the packet can be combined with the transmit packet
* and returned to the higher level function.
*
* The socket layer can exhibit a reversal in the packet order (rare).
* If the Tx order is A-B-C the return order could be A-C-B. The indexed buffer
* will reorder the packets automatically.
*
* The "redundant" option will configure two sockets and two NIC interfaces.
* Slaves are connected to both interfaces, one on the IN port and one on the
* OUT port. Packets are send via both interfaces. Any one of the connections
* (also an interconnect) can be removed and the slaves are still serviced with
* packets. The software layer will detect the possible failure modes and
* compensate. If needed the packets from interface A are resent through interface B.
* This layer if fully transparent for the higher layers.
*/
#include "osal.h"
#include "oshw.h"
#include "ethercattype.h"
#include <circle/devicenameservice.h>
#include <circle/usb/netdevice.h>
#include <string.h>
/** Redundancy modes */
enum
{
/** No redundancy, single NIC mode */
ECT_RED_NONE,
/** Double redundant NIC connecetion */
ECT_RED_DOUBLE
};
static void ecx_clear_rxbufstat(int *rxbufstat)
{
int i;
for(i = 0; i < EC_MAXBUF; i++)
{
rxbufstat[i] = EC_BUF_EMPTY;
}
}
/** Primary source MAC address used for EtherCAT.
* This address is not the MAC address used from the NIC.
* EtherCAT does not care about MAC addressing, but it is used here to
* differentiate the route the packet traverses through the EtherCAT
* segment. This is needed to find out the packet flow in redundant
* configurations. */
const uint16 priMAC[3] = { 0x0101, 0x0101, 0x0101 };
/** Secondary source MAC address used for EtherCAT. */
const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
/** second MAC word is used for identification */
#define RX_PRIM priMAC[1]
/** second MAC word is used for identification */
#define RX_SEC secMAC[1]
/** Basic setup to connect NIC to socket.
* @param[in] port = port context struct
* @param[in] ifname = Name of NIC device, f.e. "eth0"
* @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 i;
CNetDevice *nd = reinterpret_cast< CNetDevice* >(CDeviceNameService::Get()->GetDevice(ifname, FALSE));
if (!nd)
return 0;
// TODO any support for redundancy make sense? rpi has 1 native port, then now no support.
if (secondary)
return 0;
port->device = nd;
port->lastidx = 0;
port->redstate = ECT_RED_NONE;
port->stack.device = &(port->device);
port->stack.txbuf = &(port->txbuf);
port->stack.txbuflength = &(port->txbuflength);
port->stack.tempbuf = &(port->tempinbuf);
port->stack.rxbuf = &(port->rxbuf);
port->stack.rxbufstat = &(port->rxbufstat);
port->stack.rxsa = &(port->rxsa);
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
/* we use RAW packet socket, with packet type ETH_P_ECAT */
/* set flags of NIC interface, here promiscuous and broadcast */
//TODO ifr.ifr_flags = ifr.ifr_flags | IFF_PROMISC | IFF_BROADCAST;
/* setup ethernet headers in tx buffers so we don't have to repeat it */
for (i = 0; i < EC_MAXBUF; i++)
{
ec_setupheader(&(port->txbuf[i]));
port->rxbufstat[i] = EC_BUF_EMPTY;
}
ec_setupheader(&(port->txbuf2));
return 1;
}
/** Close sockets used
* @param[in] port = port context struct
* @return 0
*/
int ecx_closenic(ecx_portt *port)
{
return 0;
}
/** Fill buffer with ethernet header structure.
* Destination MAC is always broadcast.
* Ethertype is always ETH_P_ECAT.
* @param[out] p = buffer
*/
void ec_setupheader(void *p)
{
ec_etherheadert *bp;
bp = reinterpret_cast< ec_etherheadert* >(p);
bp->da0 = oshw_htons(0xffff);
bp->da1 = oshw_htons(0xffff);
bp->da2 = oshw_htons(0xffff);
bp->sa0 = oshw_htons(priMAC[0]);
bp->sa1 = oshw_htons(priMAC[1]);
bp->sa2 = oshw_htons(priMAC[2]);
bp->etype = oshw_htons(ETH_P_ECAT);
}
/** Get new frame identifier index and allocate corresponding rx buffer.
* @param[in] port = port context struct
* @return new index.
*/
int ecx_getindex(ecx_portt *port)
{
int idx;
int cnt;
idx = port->lastidx + 1;
/* index can't be larger than buffer array */
if (idx >= EC_MAXBUF)
{
idx = 0;
}
cnt = 0;
/* try to find unused index */
while ((port->rxbufstat[idx] != EC_BUF_EMPTY) && (cnt < EC_MAXBUF))
{
idx++;
cnt++;
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;
return idx;
}
/** Set rx buffer status.
* @param[in] port = port context struct
* @param[in] idx = index in buffer array
* @param[in] bufstat = status to set
*/
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
{
port->rxbufstat[idx] = bufstat;
if (port->redstate != ECT_RED_NONE)
port->redport->rxbufstat[idx] = bufstat;
}
/** Transmit buffer over socket (non blocking).
* @param[in] port = port context struct
* @param[in] idx = index in tx buffer array
* @param[in] stacknumber = 0=Primary 1=Secondary stack
* @return socket send result
*/
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
{
int lp;
ec_stackT *stack;
if (!stacknumber)
{
stack = &(port->stack);
}
else
{
stack = &(port->redport->stack);
}
lp = (*stack->txbuflength)[idx];
CNetDevice *nd = reinterpret_cast< CNetDevice* >(*stack->device);
boolean rval = nd->SendFrame((*stack->txbuf)[idx], lp);
(*stack->rxbufstat)[idx] = EC_BUF_TX;
return rval ? lp : -1;
}
/** Transmit buffer over socket (non blocking).
* @param[in] port = port context struct
* @param[in] idx = index in tx buffer array
* @return socket send result
*/
int ecx_outframe_red(ecx_portt *port, int idx)
{
ec_comt *datagramP;
ec_etherheadert *ehp;
int rval;
ehp = (ec_etherheadert *)&(port->txbuf[idx]);
/* rewrite MAC source address 1 to primary */
ehp->sa1 = oshw_htons(priMAC[1]);
/* 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]);
/* write index to frame */
datagramP->index = idx;
/* rewrite MAC source address 1 to secondary */
ehp->sa1 = oshw_htons(secMAC[1]);
/* transmit over secondary socket */
CNetDevice *nd = reinterpret_cast< CNetDevice* >(port->redport->device);
nd->SendFrame(&(port->txbuf2), port->txbuflength2);
port->redport->rxbufstat[idx] = EC_BUF_TX;
}
return rval;
}
/** Non blocking read of socket. Put frame in temporary buffer.
* @param[in] port = port context struct
* @param[in] stacknumber = 0=primary 1=secondary stack
* @return >0 if frame is available and read
*/
static int ecx_recvpkt(ecx_portt *port, int stacknumber)
{
int lp;
unsigned bytesrx;
ec_stackT *stack;
if (!stacknumber)
{
stack = &(port->stack);
}
else
{
stack = &(port->redport->stack);
}
lp = sizeof(port->tempinbuf);
CNetDevice *nd = reinterpret_cast< CNetDevice* >(*stack->device);
boolean rval = nd->ReceiveFrame((*stack->tempbuf), &bytesrx);
port->tempinbufs = bytesrx;
return rval && (bytesrx > 0);
}
/** Non blocking receive frame function. Uses RX buffer and index to combine
* read frame with transmitted frame. To compensate for received frames that
* are out-of-order all frames are stored in their respective indexed buffer.
* If a frame was placed in the buffer previously, the function retreives it
* from that buffer index without calling ec_recvpkt. If the requested index
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
* 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
* @return Workcounter if a frame is found with corresponding index, otherwise
* EC_NOFRAME or EC_OTHERFRAME.
*/
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
{
uint16 l;
int rval;
int idxf;
ec_etherheadert *ehp;
ec_comt *ecp;
ec_stackT *stack;
ec_buf_circleT *rxbuf;
if (!stacknumber)
{
stack = &(port->stack);
}
else
{
stack = &(port->redport->stack);
}
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))
{
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
/* return WKC */
rval = ((*rxbuf)[l] + ((uint16)(*rxbuf)[l + 1] << 8));
/* mark as completed */
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
}
else
{
/* non blocking call to retrieve frame from socket */
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]);
l = etohs(ecp->elength) & 0x0fff;
idxf = ecp->index;
/* found index equals reqested index ? */
if (idxf == idx)
{
/* yes, put it in the buffer array (strip ethernet header) */
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
/* return WKC */
rval = ((*rxbuf)[l] + ((uint16)((*rxbuf)[l + 1]) << 8));
/* mark as completed */
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
/* store MAC source word 1 for redundant routing info */
(*stack->rxsa)[idx] = oshw_ntohs(ehp->sa1);
}
else
{
/* check if index exist and someone is waiting for it */
if (idxf < EC_MAXBUF && (*stack->rxbufstat)[idxf] == EC_BUF_TX)
{
rxbuf = &(*stack->rxbuf)[idxf];
/* put it in the buffer array (strip ethernet header) */
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idxf] - ETH_HEADERSIZE);
/* mark as received */
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
(*stack->rxsa)[idxf] = oshw_ntohs(ehp->sa1);
}
else
{
/* strange things happend */
}
}
}
}
}
/* WKC if mathing frame found */
return rval;
}
/** Blocking redundant receive frame function. If redundant mode is not active then
* 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.
*
* @param[in] port = port context struct
* @param[in] idx = requested index of frame
* @param[in] timer = absolute timeout time
* @return Workcounter if a frame is found with corresponding index, otherwise
* EC_NOFRAME.
*/
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
{
osal_timert timer2;
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
{
/* 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 */
} 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)
{
/* primrx if the reveived MAC source on primary socket */
primrx = 0;
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
/* 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)) )
{
/* 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 */
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
{
/* If both primary and secondary have partial connection retransmit the primary received
* 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
{
/* 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
* @param[in] idx = requested index of frame
* @param[in] timeout = timeout in us
* @return Workcounter if a frame is found with corresponding index, otherwise
* EC_NOFRAME.
*/
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)
{
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
}
return wkc;
}
/** Blocking send and recieve frame function. Used for non processdata frames.
* A datagram is build into a frame and transmitted via this function. It waits
* for an answer and returns the workcounter. The function retries if time is
* left and the result is WKC=0 or no frame received.
*
* The function calls ec_outframe_red() and ec_waitinframe_red().
*
* @param[in] port = port context struct
* @param[in] idx = index of frame
* @param[in] timeout = timeout in us
* @return Workcounter or EC_NOFRAME
*/
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
{
int wkc = EC_NOFRAME;
osal_timert timer1, timer2;
osal_timer_start (&timer1, timeout);
do
{
/* tx frame on primary and if in redundant mode a dummy on secondary */
ecx_outframe_red(port, idx);
if (timeout < EC_TIMEOUTRET)
{
osal_timer_start (&timer2, timeout);
}
else
{
/* normally use partial timout for rx */
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 */
} 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)
{
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
}
return wkc;
}
#ifdef EC_VER1
int ec_setupnic(const char *ifname, int secondary)
{
return ecx_setupnic(&ecx_port, ifname, secondary);
}
int ec_closenic(void)
{
return ecx_closenic(&ecx_port);
}
int ec_getindex(void)
{
return ecx_getindex(&ecx_port);
}
void ec_setbufstat(int idx, int bufstat)
{
ecx_setbufstat(&ecx_port, idx, bufstat);
}
int ec_outframe(int idx, int stacknumber)
{
return ecx_outframe(&ecx_port, idx, stacknumber);
}
int ec_outframe_red(int idx)
{
return ecx_outframe_red(&ecx_port, idx);
}
int ec_inframe(int idx, int stacknumber)
{
return ecx_inframe(&ecx_port, idx, stacknumber);
}
int ec_waitinframe(int idx, int timeout)
{
return ecx_waitinframe(&ecx_port, idx, timeout);
}
int ec_srconfirm(int idx, int timeout)
{
return ecx_srconfirm(&ecx_port, idx, timeout);
}
#endif

View File

@ -0,0 +1,120 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for nicdrv.cpp
*/
#ifndef _nicdrvh_
#define _nicdrvh_
#ifdef __cplusplus
extern "C"
{
#endif
// CNetDevice requires buffer size 1600
#define FRAME_BUFFER_SIZE 1600
typedef uint8 ec_buf_circleT[FRAME_BUFFER_SIZE];
/** pointer structure to Tx and Rx stacks */
typedef struct
{
/** socket connection used */
void **device;
/** tx buffer */
ec_buf_circleT (*txbuf)[EC_MAXBUF];
/** tx buffer lengths */
int (*txbuflength)[EC_MAXBUF];
/** temporary receive buffer */
ec_buf_circleT *tempbuf;
/** rx buffers */
ec_buf_circleT (*rxbuf)[EC_MAXBUF];
/** rx buffer status fields */
int (*rxbufstat)[EC_MAXBUF];
/** received MAC source address (middle word) */
int (*rxsa)[EC_MAXBUF];
} ec_stackT;
/** pointer structure to buffers for redundant port */
typedef struct
{
ec_stackT stack;
void *device;
/** rx buffers */
ec_buf_circleT rxbuf[EC_MAXBUF];
/** rx buffer status */
int rxbufstat[EC_MAXBUF];
/** rx MAC source address */
int rxsa[EC_MAXBUF];
/** temporary rx buffer */
ec_buf_circleT tempinbuf;
} ecx_redportt;
/** pointer structure to buffers, vars and mutexes for port instantiation */
typedef struct
{
ec_stackT stack;
void *device;
/** rx buffers */
ec_buf_circleT rxbuf[EC_MAXBUF];
/** rx buffer status */
int rxbufstat[EC_MAXBUF];
/** rx MAC source address */
int rxsa[EC_MAXBUF];
/** temporary rx buffer */
ec_buf_circleT tempinbuf;
/** temporary rx buffer status */
int tempinbufs;
/** transmit buffers */
ec_buf_circleT txbuf[EC_MAXBUF];
/** transmit buffer lenghts */
int txbuflength[EC_MAXBUF];
/** temporary tx buffer */
ec_buf_circleT txbuf2;
/** temporary tx buffer length */
int txbuflength2;
/** last used frame index */
int lastidx;
/** current redundancy state */
int redstate;
/** pointer to redundancy port and buffers */
ecx_redportt *redport;
} ecx_portt;
extern const uint16 priMAC[3];
extern const uint16 secMAC[3];
#ifdef EC_VER1
extern ecx_portt ecx_port;
extern ecx_redportt ecx_redport;
int ec_setupnic(const char * ifname, int secondary);
int ec_closenic(void);
void ec_setbufstat(int idx, int bufstat);
int ec_getindex(void);
int ec_outframe(int idx, int sock);
int ec_outframe_red(int idx);
int ec_waitinframe(int idx, int timeout);
int ec_srconfirm(int idx,int timeout);
#endif
void ec_setupheader(void *p);
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
int ecx_closenic(ecx_portt *port);
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
int ecx_getindex(ecx_portt *port);
int ecx_outframe(ecx_portt *port, int idx, int sock);
int ecx_outframe_red(ecx_portt *port, int idx);
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
#ifdef __cplusplus
}
#endif
#endif

56
oshw/circle/oshw.c 100644
View File

@ -0,0 +1,56 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <machine/endian.h>
#include <osal.h>
#include <oshw.h>
/**
* Host to Network byte order (i.e. to big endian).
*
* Note that Ethercat uses little endian byte order, except for the Ethernet
* header which is big endian as usual.
*/
uint16 oshw_htons(uint16 host)
{
uint16 network = __htons(host);
return network;
}
/**
* Network (i.e. big endian) to Host byte order.
*
* Note that Ethercat uses little endian byte order, except for the Ethernet
* header which is big endian as usual.
*/
uint16 oshw_ntohs(uint16 network)
{
uint16 host = __ntohs(network);
return host;
}
/** Create list over available network adapters.
* @return First element in linked list of adapters
*/
ec_adaptert *oshw_find_adapters(void)
{
// TODO might use devicenameservice.h to check if eth1,eth2,ethX exist!
// TODO should return a copy of this, const-ness not guaranteed!
static ec_adaptert _s_native_eth = {
"eth0",
"native ethernet",
0L
};
return &_s_native_eth;
}
/** Free memory allocated memory used by adapter collection.
* @param[in] adapter = First element in linked list of adapters
* EC_NOFRAME.
*/
void oshw_free_adapters(ec_adaptert * adapter)
{
}

31
oshw/circle/oshw.h 100644
View File

@ -0,0 +1,31 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for ethercatbase.c
*/
#ifndef _oshw_
#define _oshw_
#ifdef __cplusplus
extern "C" {
#endif
#include "ethercattype.h"
#include "nicdrv.h"
#include "ethercatmain.h"
uint16 oshw_htons(uint16 hostshort);
uint16 oshw_ntohs(uint16 networkshort);
ec_adaptert *oshw_find_adapters(void);
void oshw_free_adapters(ec_adaptert * adapter);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,13 @@
TESTING SAMPLES ON RASPBERRY PI 3
To test a sample on Raspberry Pi 3, for example "slaveinfo", you need to:
- compile the slaveinfo sample, using "make",
you need arm-none-eabi- toolchain being in your PATH;
this will generate the kernel8-32.img file.
- copy all content of the "boot/" directory into an empty SD-card;
- copy "kernel8-32.img" into the SD-card;
Now your SD-card should be bootable.

View File

@ -0,0 +1,30 @@
Copyright (c) 2006, Broadcom Corporation.
Copyright (c) 2015, Raspberry Pi (Trading) Ltd
All rights reserved.
Redistribution. Redistribution and use in binary form, without
modification, are permitted provided that the following conditions are
met:
* This software may only be used for the purposes of developing for,
running or using a Raspberry Pi device.
* Redistributions must reproduce the above copyright notice and the
following disclaimer in the documentation and/or other materials
provided with the distribution.
* Neither the name of Broadcom Corporation nor the names of its suppliers
may be used to endorse or promote products derived from this software
without specific prior written permission.
DISCLAIMER. 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.

View File

@ -0,0 +1,15 @@
#
# Download the firmware files to be required for boot (requires wget)
#
# These files must be copied along with the generated kernel.img
# onto a SD(HC) card with FAT file system.
#
all: clean
wget -q -O LICENCE.broadcom https://github.com/raspberrypi/firmware/blob/master/boot/LICENCE.broadcom?raw=true
wget -q -O bootcode.bin https://github.com/raspberrypi/firmware/blob/master/boot/bootcode.bin?raw=true
wget -q -O fixup.dat https://github.com/raspberrypi/firmware/blob/master/boot/fixup.dat?raw=true
wget -q -O start.elf https://github.com/raspberrypi/firmware/blob/master/boot/start.elf?raw=true
clean:
rm -f bootcode.bin fixup.dat start.elf LICENCE.broadcom

Binary file not shown.

View File

@ -0,0 +1,5 @@
kernel=kernel8-32.img
kernel_address=0x00000000
enable_uart=1
init_uart_baud=115200
init_uart_clock=3000000

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,2 @@
*.o
kernel8*

View File

@ -0,0 +1,27 @@
#
# Makefile
#
CIRCLEHOME = ../../../libs/circle-stdlib/libs/circle
NEWLIBDIR = ../../../libs/circle-stdlib/install/arm-none-circle
SOEMBUILDDIR = ../../../build
SOEMSRCDIR = ../../../
OBJS = main.o kernel.o
include $(CIRCLEHOME)/Rules.mk
CFLAGS += -I "$(NEWLIBDIR)/include" -I $(STDDEF_INCPATH) \
-I $(SOEMSRCDIR)/soem \
-I $(SOEMSRCDIR)/osal -I $(SOEMSRCDIR)/osal/circle \
-I $(SOEMSRCDIR)/oshw -I $(SOEMSRCDIR)/oshw/circle
LIBS := $(SOEMBUILDDIR)/libsoem.a \
"$(NEWLIBDIR)/lib/libm.a" "$(NEWLIBDIR)/lib/libc.a" "$(NEWLIBDIR)/lib/libcirclenewlib.a" \
$(CIRCLEHOME)/addon/SDCard/libsdcard.a \
$(CIRCLEHOME)/lib/usb/libusb.a \
$(CIRCLEHOME)/lib/input/libinput.a \
$(CIRCLEHOME)/lib/fs/fat/libfatfs.a \
$(CIRCLEHOME)/lib/fs/libfs.a \
$(CIRCLEHOME)/lib/net/libnet.a \
$(CIRCLEHOME)/lib/sched/libsched.a \
$(CIRCLEHOME)/lib/libcircle.a

View File

@ -0,0 +1,724 @@
//
// kernel.cpp
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
#include "kernel.h"
#include <circle/usb/usb.h>
#include <circle/usb/netdevice.h>
#include <circle/usb/macaddress.h>
#include <circle/string.h>
#include <circle/macros.h>
#include <circle/debug.h>
#include <assert.h>
#include <stdio.h>
#include <math.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "ethercat.h"
char IOmap[4096];
ec_ODlistt ODlist;
ec_OElistt OElist;
boolean printSDO = FALSE;
boolean printMAP = FALSE;
char usdo[128];
char hstr[1024];
char* dtype2string(uint16 dtype)
{
switch(dtype)
{
case ECT_BOOLEAN:
sprintf(hstr, "BOOLEAN");
break;
case ECT_INTEGER8:
sprintf(hstr, "INTEGER8");
break;
case ECT_INTEGER16:
sprintf(hstr, "INTEGER16");
break;
case ECT_INTEGER32:
sprintf(hstr, "INTEGER32");
break;
case ECT_INTEGER24:
sprintf(hstr, "INTEGER24");
break;
case ECT_INTEGER64:
sprintf(hstr, "INTEGER64");
break;
case ECT_UNSIGNED8:
sprintf(hstr, "UNSIGNED8");
break;
case ECT_UNSIGNED16:
sprintf(hstr, "UNSIGNED16");
break;
case ECT_UNSIGNED32:
sprintf(hstr, "UNSIGNED32");
break;
case ECT_UNSIGNED24:
sprintf(hstr, "UNSIGNED24");
break;
case ECT_UNSIGNED64:
sprintf(hstr, "UNSIGNED64");
break;
case ECT_REAL32:
sprintf(hstr, "REAL32");
break;
case ECT_REAL64:
sprintf(hstr, "REAL64");
break;
case ECT_BIT1:
sprintf(hstr, "BIT1");
break;
case ECT_BIT2:
sprintf(hstr, "BIT2");
break;
case ECT_BIT3:
sprintf(hstr, "BIT3");
break;
case ECT_BIT4:
sprintf(hstr, "BIT4");
break;
case ECT_BIT5:
sprintf(hstr, "BIT5");
break;
case ECT_BIT6:
sprintf(hstr, "BIT6");
break;
case ECT_BIT7:
sprintf(hstr, "BIT7");
break;
case ECT_BIT8:
sprintf(hstr, "BIT8");
break;
case ECT_VISIBLE_STRING:
sprintf(hstr, "VISIBLE_STRING");
break;
case ECT_OCTET_STRING:
sprintf(hstr, "OCTET_STRING");
break;
default:
sprintf(hstr, "Type 0x%4.4X", dtype);
}
return hstr;
}
char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
{
int l = sizeof(usdo) - 1, i;
uint8 *u8;
int8 *i8;
uint16 *u16;
int16 *i16;
uint32 *u32;
int32 *i32;
uint64 *u64;
int64 *i64;
float *sr;
double *dr;
char es[32];
memset(&usdo, 0, 128);
ec_SDOread(slave, index, subidx, FALSE, &l, &usdo, EC_TIMEOUTRXM);
if (EcatError)
{
return ec_elist2string();
}
else
{
switch(dtype)
{
case ECT_BOOLEAN:
u8 = (uint8*) &usdo[0];
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);
break;
case ECT_INTEGER16:
i16 = (int16*) &usdo[0];
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);
break;
case ECT_INTEGER64:
i64 = (int64*) &usdo[0];
sprintf(hstr, "0x%16.16" PRIx64 " %" PRId64, *i64, *i64);
break;
case ECT_UNSIGNED8:
u8 = (uint8*) &usdo[0];
sprintf(hstr, "0x%2.2x %u", *u8, *u8);
break;
case ECT_UNSIGNED16:
u16 = (uint16*) &usdo[0];
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);
break;
case ECT_UNSIGNED64:
u64 = (uint64*) &usdo[0];
sprintf(hstr, "0x%16.16" PRIx64 " %" PRIu64, *u64, *u64);
break;
case ECT_REAL32:
sr = (float*) &usdo[0];
sprintf(hstr, "%f", *sr);
break;
case ECT_REAL64:
dr = (double*) &usdo[0];
sprintf(hstr, "%f", *dr);
break;
case ECT_BIT1:
case ECT_BIT2:
case ECT_BIT3:
case ECT_BIT4:
case ECT_BIT5:
case ECT_BIT6:
case ECT_BIT7:
case ECT_BIT8:
u8 = (uint8*) &usdo[0];
sprintf(hstr, "0x%x", *u8);
break;
case ECT_VISIBLE_STRING:
strcpy(hstr, usdo);
break;
case ECT_OCTET_STRING:
hstr[0] = 0x00;
for (i = 0 ; i < l ; i++)
{
sprintf(es, "0x%2.2x ", usdo[i]);
strcat( hstr, es);
}
break;
default:
sprintf(hstr, "Unknown type");
}
return hstr;
}
}
/** Read PDO assign structure */
int si_PDOassign(uint16 slave, uint16 PDOassign, int mapoffset, int bitoffset)
{
uint16 idxloop, nidx, subidxloop, rdat, idx, subidx;
uint8 subcnt;
int wkc, bsize = 0, rdl;
int32 rdat2;
uint8 bitlen, obj_subidx;
uint16 obj_idx;
int abs_offset, abs_bit;
rdl = sizeof(rdat); rdat = 0;
/* read PDO assign subindex 0 ( = number of PDO's) */
wkc = ec_SDOread(slave, PDOassign, 0x00, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
rdat = etohs(rdat);
/* positive result from slave ? */
if ((wkc > 0) && (rdat > 0))
{
/* number of available sub indexes */
nidx = rdat;
bsize = 0;
/* read all PDO's */
for (idxloop = 1; idxloop <= nidx; idxloop++)
{
rdl = sizeof(rdat); rdat = 0;
/* read PDO assign */
wkc = ec_SDOread(slave, PDOassign, (uint8)idxloop, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
/* result is index of PDO */
idx = etohl(rdat);
if (idx > 0)
{
rdl = sizeof(subcnt); subcnt = 0;
/* read number of subindexes of PDO */
wkc = ec_SDOread(slave,idx, 0x00, FALSE, &rdl, &subcnt, EC_TIMEOUTRXM);
subidx = subcnt;
/* for each subindex */
for (subidxloop = 1; subidxloop <= subidx; subidxloop++)
{
rdl = sizeof(rdat2); rdat2 = 0;
/* read SDO that is mapped in PDO */
wkc = ec_SDOread(slave, idx, (uint8)subidxloop, FALSE, &rdl, &rdat2, EC_TIMEOUTRXM);
rdat2 = etohl(rdat2);
/* extract bitlength of SDO */
bitlen = LO_BYTE(rdat2);
bsize += bitlen;
obj_idx = (uint16)(rdat2 >> 16);
obj_subidx = (uint8)((rdat2 >> 8) & 0x000000ff);
abs_offset = mapoffset + (bitoffset / 8);
abs_bit = bitoffset % 8;
ODlist.Slave = slave;
ODlist.Index[0] = obj_idx;
OElist.Entries = 0;
wkc = 0;
/* read object entry from dictionary if not a filler (0x0000:0x00) */
if(obj_idx || obj_subidx)
wkc = ec_readOEsingle(0, obj_subidx, &ODlist, &OElist);
printf(" [0x%4.4X.%1d] 0x%4.4X:0x%2.2X 0x%2.2X", abs_offset, abs_bit, obj_idx, obj_subidx, bitlen);
if((wkc > 0) && OElist.Entries)
{
printf(" %-12s %s\n", dtype2string(OElist.DataType[obj_subidx]), OElist.Name[obj_subidx]);
}
else
printf("\n");
bitoffset += bitlen;
};
};
};
};
/* return total found bitlength (PDO) */
return bsize;
}
int si_map_sdo(int slave)
{
int wkc, rdl;
int retVal = 0;
uint8 nSM, iSM, tSM;
int Tsize, outputs_bo, inputs_bo;
uint8 SMt_bug_add;
printf("PDO mapping according to CoE :\n");
SMt_bug_add = 0;
outputs_bo = 0;
inputs_bo = 0;
rdl = sizeof(nSM); nSM = 0;
/* read SyncManager Communication Type object count */
wkc = ec_SDOread(slave, ECT_SDO_SMCOMMTYPE, 0x00, FALSE, &rdl, &nSM, EC_TIMEOUTRXM);
/* positive result from slave ? */
if ((wkc > 0) && (nSM > 2))
{
/* make nSM equal to number of defined SM */
nSM--;
/* limit to maximum number of SM defined, if true the slave can't be configured */
if (nSM > EC_MAXSM)
nSM = EC_MAXSM;
/* iterate for every SM type defined */
for (iSM = 2 ; iSM <= nSM ; iSM++)
{
rdl = sizeof(tSM); tSM = 0;
/* read SyncManager Communication Type */
wkc = ec_SDOread(slave, ECT_SDO_SMCOMMTYPE, iSM + 1, FALSE, &rdl, &tSM, EC_TIMEOUTRXM);
if (wkc > 0)
{
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
printf("Activated SM type workaround, possible incorrect mapping.\n");
}
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;
}
}
}
}
/* found some I/O bits ? */
if ((outputs_bo > 0) || (inputs_bo > 0))
retVal = 1;
return retVal;
}
int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
{
uint16 a , w, c, e, er, Size;
uint8 eectl;
uint16 obj_idx;
uint8 obj_subidx;
uint8 obj_name;
uint8 obj_datatype;
uint8 bitlen;
int totalsize;
ec_eepromPDOt eepPDO;
ec_eepromPDOt *PDO;
int abs_offset, abs_bit;
char str_name[EC_MAXNAME + 1];
eectl = ec_slave[slave].eep_pdi;
Size = 0;
totalsize = 0;
PDO = &eepPDO;
PDO->nPDO = 0;
PDO->Length = 0;
PDO->Index[1] = 0;
for (c = 0 ; c < EC_MAXSM ; c++) PDO->SMbitsize[c] = 0;
if (t > 1)
t = 1;
PDO->Startpos = ec_siifind(slave, ECT_SII_PDO + t);
if (PDO->Startpos > 0)
{
a = PDO->Startpos;
w = ec_siigetbyte(slave, a++);
w += (ec_siigetbyte(slave, a++) << 8);
PDO->Length = w;
c = 1;
/* traverse through all PDOs */
do
{
PDO->nPDO++;
PDO->Index[PDO->nPDO] = ec_siigetbyte(slave, a++);
PDO->Index[PDO->nPDO] += (ec_siigetbyte(slave, a++) << 8);
PDO->BitSize[PDO->nPDO] = 0;
c++;
/* number of entries in PDO */
e = ec_siigetbyte(slave, a++);
PDO->SyncM[PDO->nPDO] = ec_siigetbyte(slave, a++);
a++;
obj_name = ec_siigetbyte(slave, a++);
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);
if (t)
printf(" SM%1d RXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
else
printf(" SM%1d TXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
printf(" addr b index: sub bitl data_type name\n");
/* read all entries defined in PDO */
for (er = 1; er <= e; er++)
{
c += 4;
obj_idx = ec_siigetbyte(slave, a++);
obj_idx += (ec_siigetbyte(slave, a++) << 8);
obj_subidx = ec_siigetbyte(slave, a++);
obj_name = ec_siigetbyte(slave, a++);
obj_datatype = ec_siigetbyte(slave, a++);
bitlen = ec_siigetbyte(slave, a++);
abs_offset = mapoffset + (bitoffset / 8);
abs_bit = bitoffset % 8;
PDO->BitSize[PDO->nPDO] += bitlen;
a += 2;
/* skip entry if filler (0x0000:0x00) */
if(obj_idx || obj_subidx)
{
str_name[0] = 0;
if(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);
}
bitoffset += bitlen;
totalsize += bitlen;
}
PDO->SMbitsize[ PDO->SyncM[PDO->nPDO] ] += PDO->BitSize[PDO->nPDO];
Size += PDO->BitSize[PDO->nPDO];
c++;
}
else /* PDO deactivated because SM is 0xff or > EC_MAXSM */
{
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);
}
if (eectl) ec_eeprom2pdi(slave); /* if eeprom control was previously pdi then restore */
return totalsize;
}
int si_map_sii(int slave)
{
int retVal = 0;
int Tsize, outputs_bo, inputs_bo;
printf("PDO mapping according to SII :\n");
outputs_bo = 0;
inputs_bo = 0;
/* read the assign RXPDOs */
Tsize = si_siiPDO(slave, 1, (int)(ec_slave[slave].outputs - (uint8*)&IOmap), outputs_bo );
outputs_bo += Tsize;
/* read the assign TXPDOs */
Tsize = si_siiPDO(slave, 0, (int)(ec_slave[slave].inputs - (uint8*)&IOmap), inputs_bo );
inputs_bo += Tsize;
/* found some I/O bits ? */
if ((outputs_bo > 0) || (inputs_bo > 0))
retVal = 1;
return retVal;
}
void si_sdo(int cnt)
{
int i, j;
ODlist.Entries = 0;
memset(&ODlist, 0, sizeof(ODlist));
if( ec_readODlist(cnt, &ODlist))
{
printf(" CoE Object Description found, %d entries.\n",ODlist.Entries);
for( i = 0 ; i < ODlist.Entries ; i++)
{
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]);
memset(&OElist, 0, sizeof(OElist));
ec_readOE(i, &ODlist, &OElist);
while(EcatError) printf("%s", ec_elist2string());
for( j = 0 ; j < ODlist.MaxSub[i]+1 ; j++)
{
if ((OElist.DataType[j] > 0) && (OElist.BitLength[j] > 0))
{
printf(" Sub: %2.2x Datatype: %4.4x Bitlength: %4.4x Obj.access: %4.4x Name: %s\n",
j, OElist.DataType[j], OElist.BitLength[j], OElist.ObjAccess[j], OElist.Name[j]);
if ((OElist.ObjAccess[j] & 0x0007))
{
printf(" Value :%s\n", SDO2string(cnt, ODlist.Index[i], j, OElist.DataType[j]));
}
}
}
}
}
else
{
while(EcatError) printf("%s", ec_elist2string());
}
}
void slaveinfo(const 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 )
{
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;
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);
if (ec_slave[0].state != EC_STATE_SAFE_OP )
{
printf("Not all slaves reached safe operational state.\n");
ec_readstate();
for(i = 1; i<=ec_slavecount ; i++)
{
if(ec_slave[i].state != EC_STATE_SAFE_OP)
{
printf("Slave %d State=%2x StatusCode=%4x : %s\n",
i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
}
}
}
ec_readstate();
for( cnt = 1 ; cnt <= ec_slavecount ; cnt++)
{
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, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits,
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 & 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);
for(nSM = 0 ; nSM < EC_MAXSM ; nSM++)
{
if(ec_slave[cnt].SM[nSM].StartAddr > 0)
printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, ec_slave[cnt].SM[nSM].StartAddr, ec_slave[cnt].SM[nSM].SMlength,
(int)ec_slave[cnt].SM[nSM].SMflags, ec_slave[cnt].SMtype[nSM]);
}
for(j = 0 ; j < ec_slave[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)ec_slave[cnt].FMMU[j].LogStart, ec_slave[cnt].FMMU[j].LogLength, ec_slave[cnt].FMMU[j].LogStartbit,
ec_slave[cnt].FMMU[j].LogEndbit, ec_slave[cnt].FMMU[j].PhysStart, ec_slave[cnt].FMMU[j].PhysStartBit,
ec_slave[cnt].FMMU[j].FMMUtype, ec_slave[cnt].FMMU[j].FMMUactive);
}
printf(" FMMUfunc 0:%d 1:%d 2:%d 3:%d\n",
ec_slave[cnt].FMMU0func, ec_slave[cnt].FMMU1func, ec_slave[cnt].FMMU2func, ec_slave[cnt].FMMU3func);
printf(" MBX length wr: %d rd: %d MBX protocols : %2.2x\n", ec_slave[cnt].mbx_l, ec_slave[cnt].mbx_rl, ec_slave[cnt].mbx_proto);
ssigen = ec_siifind(cnt, ECT_SII_GENERAL);
/* SII general section */
if (ssigen)
{
ec_slave[cnt].CoEdetails = ec_siigetbyte(cnt, ssigen + 0x07);
ec_slave[cnt].FoEdetails = ec_siigetbyte(cnt, ssigen + 0x08);
ec_slave[cnt].EoEdetails = ec_siigetbyte(cnt, ssigen + 0x09);
ec_slave[cnt].SoEdetails = ec_siigetbyte(cnt, ssigen + 0x0a);
if((ec_siigetbyte(cnt, ssigen + 0x0d) & 0x02) > 0)
{
ec_slave[cnt].blockLRW = 1;
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;
}
printf(" CoE details: %2.2x FoE details: %2.2x EoE details: %2.2x SoE details: %2.2x\n",
ec_slave[cnt].CoEdetails, ec_slave[cnt].FoEdetails, ec_slave[cnt].EoEdetails, ec_slave[cnt].SoEdetails);
printf(" Ebus current: %d[mA]\n only LRD/LWR:%d\n",
ec_slave[cnt].Ebuscurrent, ec_slave[cnt].blockLRW);
if ((ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE) && printSDO)
si_sdo(cnt);
if(printMAP)
{
if (ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE)
si_map_sdo(cnt);
else
si_map_sii(cnt);
}
}
}
else
{
printf("No slaves found!\n");
}
printf("End slaveinfo, close socket\n");
/* stop SOEM, close socket */
ec_close();
}
else
{
printf("No socket connection on %s\nExcecute as root\n",ifname);
}
}
char ifbuf[1024];
namespace
{
char const FromKernel[] = "kernel";
}
CKernel::CKernel (void)
: m_Screen (m_Options.GetWidth (), m_Options.GetHeight ()),
m_Timer (&m_Interrupt),
m_Logger (m_Options.GetLogLevel (), &m_Timer),
m_DWHCI (&m_Interrupt, &m_Timer)
{
m_ActLED.Blink (5); // show we are alive
}
CKernel::~CKernel (void)
{
}
boolean CKernel::Initialize (void)
{
boolean bOK = TRUE;
if (bOK)
{
bOK = m_Screen.Initialize ();
}
if (bOK)
{
bOK = m_Serial.Initialize (115200);
}
if (bOK)
{
CDevice *pTarget = m_DeviceNameService.GetDevice (m_Options.GetLogDevice (), FALSE);
if (pTarget == 0)
{
pTarget = &m_Screen;
}
bOK = m_Logger.Initialize (pTarget);
}
if (bOK)
{
bOK = m_Interrupt.Initialize ();
}
if (bOK)
{
bOK = m_Timer.Initialize ();
}
if (bOK)
{
bOK = m_DWHCI.Initialize ();
}
return bOK;
}
TShutdownMode CKernel::Run (void)
{
m_Logger.Write (FromKernel, LogNotice, "Compile time: " __DATE__ " " __TIME__);
CNetDevice *pEth0 = (CNetDevice *) m_DeviceNameService.GetDevice ("eth0", FALSE);
if (pEth0 == 0)
{
m_Logger.Write (FromKernel, LogError, "Net device not found");
return ShutdownHalt;
}
// wait for Ethernet PHY to come up
m_Timer.MsDelay (2000);
m_Logger.Write (FromKernel, LogNotice, "EtherCAT Master Demo");
printSDO = TRUE;
printMAP = TRUE;
slaveinfo("eth0");
m_Logger.Write (FromKernel, LogNotice, "EtherCAT Master Demo finished");
return ShutdownHalt;
}

View File

@ -0,0 +1,67 @@
//
// kernel.h
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
#ifndef _kernel_h
#define _kernel_h
#include <circle/memory.h>
#include <circle/actled.h>
#include <circle/koptions.h>
#include <circle/devicenameservice.h>
#include <circle/screen.h>
#include <circle/serial.h>
#include <circle/exceptionhandler.h>
#include <circle/interrupt.h>
#include <circle/timer.h>
#include <circle/logger.h>
#include <circle/usb/dwhcidevice.h>
#include <circle/types.h>
enum TShutdownMode
{
ShutdownNone,
ShutdownHalt,
ShutdownReboot
};
class CKernel
{
public:
CKernel (void);
~CKernel (void);
boolean Initialize (void);
TShutdownMode Run (void);
private:
// do not change this order
CMemorySystem m_Memory;
CActLED m_ActLED;
CKernelOptions m_Options;
CDeviceNameService m_DeviceNameService;
CScreenDevice m_Screen;
CSerialDevice m_Serial;
CExceptionHandler m_ExceptionHandler;
CInterruptSystem m_Interrupt;
CTimer m_Timer;
CLogger m_Logger;
CDWHCIDevice m_DWHCI;
};
#endif

View File

@ -0,0 +1,44 @@
//
// main.c
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
#include "kernel.h"
#include <circle/startup.h>
int main (void)
{
// cannot return here because some destructors used in CKernel are not implemented
CKernel Kernel;
if (!Kernel.Initialize ())
{
halt ();
return EXIT_HALT;
}
TShutdownMode ShutdownMode = Kernel.Run ();
switch (ShutdownMode)
{
case ShutdownReboot:
reboot ();
return EXIT_REBOOT;
case ShutdownHalt:
default:
halt ();
return EXIT_HALT;
}
}