mirror of
https://github.com/OpenEtherCATsociety/SOEM.git
synced 2026-02-06 18:30:09 +08:00
Add more samples
Change-Id: I6bf219887efd88a69a257815f1974759d56fd3c3
This commit is contained in:
@@ -148,10 +148,17 @@ install(FILES
|
||||
)
|
||||
|
||||
if(SOEM_BUILD_UTILS)
|
||||
add_subdirectory(samples/simple_ng)
|
||||
add_subdirectory(samples/slaveinfo)
|
||||
add_subdirectory(samples/eepromtool)
|
||||
add_subdirectory(samples/firm_update)
|
||||
add_subdirectory(samples/simple_ng)
|
||||
add_subdirectory(samples/simple_test)
|
||||
add_subdirectory(samples/slaveinfo)
|
||||
|
||||
if (${CMAKE_SYSTEM_NAME} STREQUAL Linux)
|
||||
add_subdirectory(samples/coetest)
|
||||
add_subdirectory(samples/eoe_test)
|
||||
add_subdirectory(samples/red_test)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
# Platform configuration
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
"binaryDir": "build/${presetName}",
|
||||
"cacheVariables": {
|
||||
"CMAKE_EXPORT_COMPILE_COMMANDS": true,
|
||||
"CMAKE_COMPILE_WARNING_AS_ERROR": true,
|
||||
"CMAKE_FIND_NO_INSTALL_PREFIX": true
|
||||
}
|
||||
}, {
|
||||
|
||||
@@ -16,29 +16,24 @@ target_include_directories(soem PUBLIC
|
||||
$<INSTALL_INTERFACE:include/soem>
|
||||
)
|
||||
|
||||
target_compile_options(soem PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
)
|
||||
|
||||
target_compile_options(slaveinfo PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
)
|
||||
|
||||
target_compile_options(simple_test PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
)
|
||||
|
||||
target_compile_options(eepromtool PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
)
|
||||
foreach(target IN ITEMS
|
||||
soem
|
||||
coetest
|
||||
eepromtool
|
||||
eni_test
|
||||
eoe_test
|
||||
firm_update
|
||||
red_test
|
||||
simple_ng
|
||||
simple_test
|
||||
slaveinfo)
|
||||
if (TARGET ${target})
|
||||
target_compile_options(${target} PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
target_link_libraries(soem PUBLIC pthread rt)
|
||||
|
||||
|
||||
@@ -17,18 +17,32 @@ target_include_directories(soem PUBLIC
|
||||
$<INSTALL_INTERFACE:include/soem>
|
||||
)
|
||||
|
||||
target_compile_options(soem PRIVATE
|
||||
$<$<C_COMPILER_ID:MSVC>:
|
||||
/D _CRT_SECURE_NO_WARNINGS
|
||||
/WX
|
||||
>
|
||||
$<$<C_COMPILER_ID:GNU>:
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
-Wno-unused-parameter
|
||||
>
|
||||
)
|
||||
foreach(target IN ITEMS
|
||||
soem
|
||||
coetest
|
||||
eepromtool
|
||||
eni_test
|
||||
eoe_test
|
||||
firm_update
|
||||
red_test
|
||||
simple_ng
|
||||
simple_test
|
||||
slaveinfo)
|
||||
if (TARGET ${target})
|
||||
target_compile_options(${target} PRIVATE
|
||||
$<$<C_COMPILER_ID:MSVC>:
|
||||
/D _CRT_SECURE_NO_WARNINGS
|
||||
/W3
|
||||
>
|
||||
$<$<C_COMPILER_ID:GNU>:
|
||||
-Wall
|
||||
-Wextra
|
||||
-Wno-unused-parameter
|
||||
>
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
|
||||
if(CMAKE_SIZEOF_VOID_P EQUAL 8)
|
||||
set(WPCAP_LIB_PATH ${SOEM_SOURCE_DIR}/oshw/win32/wpcap/Lib/x64)
|
||||
|
||||
@@ -26,13 +26,26 @@ target_include_directories(soem PUBLIC
|
||||
$<INSTALL_INTERFACE:include/soem>
|
||||
)
|
||||
|
||||
target_compile_options(soem PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Werror
|
||||
-Wno-unused-parameter
|
||||
-Wno-format
|
||||
)
|
||||
foreach(target IN ITEMS
|
||||
soem
|
||||
coetest
|
||||
eepromtool
|
||||
eni_test
|
||||
eoe_test
|
||||
firm_update
|
||||
red_test
|
||||
simple_ng
|
||||
simple_test
|
||||
slaveinfo)
|
||||
if (TARGET ${target})
|
||||
target_compile_options(${target} PRIVATE
|
||||
-Wall
|
||||
-Wextra
|
||||
-Wno-unused-parameter
|
||||
-Wno-format
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
install(FILES
|
||||
osal/rtk/osal_defs.h
|
||||
|
||||
3
samples/coetest/CMakeLists.txt
Normal file
3
samples/coetest/CMakeLists.txt
Normal file
@@ -0,0 +1,3 @@
|
||||
add_executable(coetest coetest.c)
|
||||
target_link_libraries(coetest soem)
|
||||
install(TARGETS coetest DESTINATION bin)
|
||||
@@ -10,12 +10,8 @@
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
#include <unistd.h>
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <pthread.h>
|
||||
|
||||
#include "ethercat.h"
|
||||
#include "soem/soem.h"
|
||||
|
||||
boolean forceByteAlignment = FALSE;
|
||||
#define EC_TIMEOUTMON 500
|
||||
@@ -29,6 +25,49 @@ int64_t cycletime = 1000000;
|
||||
#define NSEC_PER_MSEC 1000000
|
||||
#define NSEC_PER_SEC 1000000000
|
||||
|
||||
static ec_slavet ec_slave[EC_MAXSLAVE];
|
||||
static int ec_slavecount;
|
||||
static ec_groupt ec_group[EC_MAXGROUP];
|
||||
static uint8 ec_esibuf[EC_MAXEEPBUF];
|
||||
static uint32 ec_esimap[EC_MAXEEPBITMAP];
|
||||
static ec_eringt ec_elist;
|
||||
static ec_idxstackT ec_idxstack;
|
||||
static ec_SMcommtypet ec_SMcommtype[EC_MAX_MAPT];
|
||||
static ec_PDOassignt ec_PDOassign[EC_MAX_MAPT];
|
||||
static ec_PDOdesct ec_PDOdesc[EC_MAX_MAPT];
|
||||
static ec_eepromSMt ec_SM;
|
||||
static ec_eepromFMMUt ec_FMMU;
|
||||
static boolean EcatError = FALSE;
|
||||
static int64 ec_DCtime;
|
||||
static ecx_portt ecx_port;
|
||||
static ec_mbxpoolt ec_mbxpool;
|
||||
|
||||
static ecx_contextt ctx = {
|
||||
.port = &ecx_port,
|
||||
.slavelist = &ec_slave[0],
|
||||
.slavecount = &ec_slavecount,
|
||||
.maxslave = EC_MAXSLAVE,
|
||||
.grouplist = &ec_group[0],
|
||||
.maxgroup = EC_MAXGROUP,
|
||||
.esibuf = &ec_esibuf[0],
|
||||
.esimap = &ec_esimap[0],
|
||||
.esislave = 0,
|
||||
.elist = &ec_elist,
|
||||
.idxstack = &ec_idxstack,
|
||||
.ecaterror = &EcatError,
|
||||
.DCtime = &ec_DCtime,
|
||||
.SMcommtype = &ec_SMcommtype[0],
|
||||
.PDOassign = &ec_PDOassign[0],
|
||||
.PDOdesc = &ec_PDOdesc[0],
|
||||
.eepSM = &ec_SM,
|
||||
.eepFMMU = &ec_FMMU,
|
||||
.mbxpool = &ec_mbxpool,
|
||||
.FOEhook = NULL,
|
||||
.EOEhook = NULL,
|
||||
.manualstatechange = 0,
|
||||
.userdata = NULL,
|
||||
};
|
||||
|
||||
/* add ns to timespec */
|
||||
void add_timespec(struct timespec *ts, int64 addtime)
|
||||
{
|
||||
@@ -82,7 +121,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void)
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
ht = (ts.tv_nsec / 1000000) + 1; /* round to nearest ms */
|
||||
ts.tv_nsec = ht * 1000000;
|
||||
ecx_send_processdata(&ecx_context);
|
||||
ecx_send_processdata(&ctx);
|
||||
while (1)
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
@@ -91,7 +130,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void)
|
||||
clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, &tleft);
|
||||
if (dorun > 0)
|
||||
{
|
||||
wkc = ecx_receive_processdata(&ecx_context, EC_TIMEOUTRET);
|
||||
wkc = ecx_receive_processdata(&ctx, EC_TIMEOUTRET);
|
||||
if (wkc != expectedWKC)
|
||||
dowkccheck++;
|
||||
else
|
||||
@@ -101,8 +140,8 @@ OSAL_THREAD_FUNC_RT ecatthread(void)
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
ecx_mbxhandler(&ecx_context, 0, 4);
|
||||
ecx_send_processdata(&ecx_context);
|
||||
ecx_mbxhandler(&ctx, 0, 4);
|
||||
ecx_send_processdata(&ctx);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -117,7 +156,7 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
{
|
||||
/* one ore more slaves are not responding */
|
||||
ec_group[currentgroup].docheckstate = FALSE;
|
||||
ec_readstate();
|
||||
ecx_readstate(&ctx);
|
||||
for (slave = 1; slave <= ec_slavecount; slave++)
|
||||
{
|
||||
if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
|
||||
@@ -127,17 +166,18 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
{
|
||||
printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
|
||||
ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
|
||||
ec_writestate(slave);
|
||||
ecx_writestate(&ctx, slave);
|
||||
}
|
||||
else if (ec_slave[slave].state == EC_STATE_SAFE_OP)
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
if (ec_slave[slave].mbxhandlerstate == ECT_MBXH_LOST) ec_slave[slave].mbxhandlerstate = ECT_MBXH_CYCLIC;
|
||||
ecx_writestate(&ctx, slave);
|
||||
}
|
||||
else if (ec_slave[slave].state > EC_STATE_NONE)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
if (ecx_reconfig_slave(&ctx, slave, EC_TIMEOUTMON) >= EC_STATE_PRE_OP)
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n", slave);
|
||||
@@ -146,10 +186,17 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
else if (!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
|
||||
ecx_statecheck(&ctx, slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
|
||||
if (ec_slave[slave].state == EC_STATE_NONE)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
ec_slave[slave].mbxhandlerstate = ECT_MBXH_LOST;
|
||||
/* zero input data for this slave */
|
||||
if (ec_slave[slave].Ibytes)
|
||||
{
|
||||
memset(ec_slave[slave].inputs, 0x00, ec_slave[slave].Ibytes);
|
||||
printf("zero inputs %p %d\n\r", ec_slave[slave].inputs, ec_slave[slave].Ibytes);
|
||||
}
|
||||
printf("ERROR : slave %d lost\n", slave);
|
||||
}
|
||||
}
|
||||
@@ -158,7 +205,7 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
{
|
||||
if (ec_slave[slave].state <= EC_STATE_INIT)
|
||||
{
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
if (ecx_recover_slave(&ctx, slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n", slave);
|
||||
@@ -167,7 +214,7 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
else
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d found. State %2.2x\n", slave, ec_slave[slave].state);
|
||||
printf("MESSAGE : slave %d found\n", slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -182,61 +229,61 @@ OSAL_THREAD_FUNC ecatcheck(void)
|
||||
void ethercatstartup(char *ifname)
|
||||
{
|
||||
printf("EtherCAT Startup\n");
|
||||
int rv = ecx_init(&ecx_context, ifname);
|
||||
int rv = ecx_init(&ctx, ifname);
|
||||
if (rv)
|
||||
{
|
||||
adapterisbound = 1;
|
||||
ecx_config_init(&ecx_context, FALSE);
|
||||
ecx_config_init(&ctx, FALSE);
|
||||
if (ec_slavecount > 0)
|
||||
{
|
||||
if (forceByteAlignment)
|
||||
conf_io_size = ecx_config_map_group_aligned(&ecx_context, &IOmap, 0);
|
||||
conf_io_size = ecx_config_map_group_aligned(&ctx, &IOmap, 0);
|
||||
else
|
||||
conf_io_size = ecx_config_map_group(&ecx_context, &IOmap, 0);
|
||||
expectedWKC = (ecx_context.grouplist[0].outputsWKC * 2) + ecx_context.grouplist[0].inputsWKC;
|
||||
conf_io_size = ecx_config_map_group(&ctx, &IOmap, 0);
|
||||
expectedWKC = (ctx.grouplist[0].outputsWKC * 2) + ctx.grouplist[0].inputsWKC;
|
||||
mappingdone = 1;
|
||||
ecx_configdc(&ecx_context);
|
||||
ecx_configdc(&ctx);
|
||||
int sdoslave = -1;
|
||||
for (int si = 1; si <= *ecx_context.slavecount; si++)
|
||||
for (int si = 1; si <= *ctx.slavecount; si++)
|
||||
{
|
||||
ec_slavet *slave = &ecx_context.slavelist[si];
|
||||
ec_slavet *slave = &ctx.slavelist[si];
|
||||
printf("Slave %d name:%s man:%8.8x id:%8.8x rev:%d ser:%d\n", si, slave->name, slave->eep_man, slave->eep_id, slave->eep_rev, slave->eep_ser);
|
||||
if (slave->CoEdetails > 0)
|
||||
{
|
||||
ecx_slavembxcyclic(&ecx_context, si);
|
||||
ecx_slavembxcyclic(&ctx, si);
|
||||
sdoslave = si;
|
||||
printf(" Slave added to cyclic mailbox handler\n");
|
||||
}
|
||||
}
|
||||
dorun = 1;
|
||||
osal_usleep(1000000);
|
||||
ecx_context.slavelist[0].state = EC_STATE_OPERATIONAL;
|
||||
ecx_writestate(&ecx_context, 0);
|
||||
ecx_statecheck(&ecx_context, 0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
|
||||
ctx.slavelist[0].state = EC_STATE_OPERATIONAL;
|
||||
ecx_writestate(&ctx, 0);
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
|
||||
inOP = 1;
|
||||
printf("EtherCAT OP\n");
|
||||
uint32_t aval = 0;
|
||||
int avals = sizeof(aval);
|
||||
for (int i = 0; i < 100; i++)
|
||||
{
|
||||
printf("Cycle %d timeerror %ld\n", i, timeerror);
|
||||
printf("Cycle %d timeerror %" PRId64 "\n", i, timeerror);
|
||||
if (sdoslave > 0)
|
||||
{
|
||||
aval = 0;
|
||||
int rval = ecx_SDOread(&ecx_context, sdoslave, 0x1018, 0x02, FALSE, &avals, &aval, EC_TIMEOUTRXM);
|
||||
int rval = ecx_SDOread(&ctx, sdoslave, 0x1018, 0x02, FALSE, &avals, &aval, EC_TIMEOUTRXM);
|
||||
printf(" Slave %d Rval %d Prodcode %8.8x\n", sdoslave, rval, aval);
|
||||
}
|
||||
osal_usleep(100000);
|
||||
}
|
||||
inOP = 0;
|
||||
printf("EtherCAT to safe-OP\n");
|
||||
ecx_context.slavelist[0].state = EC_STATE_SAFE_OP;
|
||||
ecx_writestate(&ecx_context, 0);
|
||||
ecx_statecheck(&ecx_context, 0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
ctx.slavelist[0].state = EC_STATE_SAFE_OP;
|
||||
ecx_writestate(&ctx, 0);
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
printf("EtherCAT to INIT\n");
|
||||
ecx_context.slavelist[0].state = EC_STATE_INIT;
|
||||
ecx_writestate(&ecx_context, 0);
|
||||
ecx_statecheck(&ecx_context, 0, EC_STATE_INIT, EC_TIMEOUTSTATE);
|
||||
ctx.slavelist[0].state = EC_STATE_INIT;
|
||||
ecx_writestate(&ctx, 0);
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_INIT, EC_TIMEOUTSTATE);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -257,16 +304,17 @@ int main(int argc, char *argv[])
|
||||
else
|
||||
{
|
||||
ec_adaptert *adapter = NULL;
|
||||
ec_adaptert *head = NULL;
|
||||
printf("Usage: coetest ifname1\nifname = eth0 for example\n");
|
||||
|
||||
printf("\nAvailable adapters:\n");
|
||||
adapter = ec_find_adapters();
|
||||
head = adapter = ec_find_adapters();
|
||||
while (adapter != NULL)
|
||||
{
|
||||
printf(" - %s (%s)\n", adapter->name, adapter->desc);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
ec_free_adapters(adapter);
|
||||
ec_free_adapters(head);
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
@@ -1,5 +1,3 @@
|
||||
|
||||
set(SOURCES eepromtool.c)
|
||||
add_executable(eepromtool ${SOURCES})
|
||||
add_executable(eepromtool eepromtool.c)
|
||||
target_link_libraries(eepromtool soem)
|
||||
install(TARGETS eepromtool DESTINATION bin)
|
||||
|
||||
@@ -360,7 +360,7 @@ void eepromtool(char *ifname, int slave, int mode, char *fname)
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ecx_init(&ctx, ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n", ifname);
|
||||
printf("ecx_init on %s succeeded.\n", ifname);
|
||||
|
||||
w = 0x0000;
|
||||
wkc = ecx_BRD(&ctx.port[0], 0x0000, ECT_REG_TYPE, sizeof(w), &w, EC_TIMEOUTSAFE); /* detect number of slaves */
|
||||
|
||||
3
samples/eoe_test/CMakeLists.txt
Normal file
3
samples/eoe_test/CMakeLists.txt
Normal file
@@ -0,0 +1,3 @@
|
||||
add_executable(eoe_test eoe_test.c)
|
||||
target_link_libraries(eoe_test soem)
|
||||
install(TARGETS eoe_test DESTINATION bin)
|
||||
File diff suppressed because it is too large
Load Diff
3
samples/firm_update/CMakeLists.txt
Normal file
3
samples/firm_update/CMakeLists.txt
Normal file
@@ -0,0 +1,3 @@
|
||||
add_executable(firm_update firm_update.c)
|
||||
target_link_libraries(firm_update soem)
|
||||
install(TARGETS firm_update DESTINATION bin)
|
||||
@@ -18,7 +18,7 @@
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include "ethercat.h"
|
||||
#include "soem/soem.h"
|
||||
|
||||
#define FWBUFSIZE (8 * 1024 * 1024)
|
||||
|
||||
@@ -30,6 +30,50 @@ char filebuffer[FWBUFSIZE]; // 8MB buffer
|
||||
int filesize;
|
||||
int j;
|
||||
uint16 argslave;
|
||||
boolean forceByteAlignment = FALSE;
|
||||
|
||||
static ec_slavet ec_slave[EC_MAXSLAVE];
|
||||
static int ec_slavecount;
|
||||
static ec_groupt ec_group[EC_MAXGROUP];
|
||||
static uint8 ec_esibuf[EC_MAXEEPBUF];
|
||||
static uint32 ec_esimap[EC_MAXEEPBITMAP];
|
||||
static ec_eringt ec_elist;
|
||||
static ec_idxstackT ec_idxstack;
|
||||
static ec_SMcommtypet ec_SMcommtype[EC_MAX_MAPT];
|
||||
static ec_PDOassignt ec_PDOassign[EC_MAX_MAPT];
|
||||
static ec_PDOdesct ec_PDOdesc[EC_MAX_MAPT];
|
||||
static ec_eepromSMt ec_SM;
|
||||
static ec_eepromFMMUt ec_FMMU;
|
||||
static boolean EcatError = FALSE;
|
||||
static int64 ec_DCtime;
|
||||
static ecx_portt ecx_port;
|
||||
static ec_mbxpoolt ec_mbxpool;
|
||||
|
||||
static ecx_contextt ctx = {
|
||||
.port = &ecx_port,
|
||||
.slavelist = &ec_slave[0],
|
||||
.slavecount = &ec_slavecount,
|
||||
.maxslave = EC_MAXSLAVE,
|
||||
.grouplist = &ec_group[0],
|
||||
.maxgroup = EC_MAXGROUP,
|
||||
.esibuf = &ec_esibuf[0],
|
||||
.esimap = &ec_esimap[0],
|
||||
.esislave = 0,
|
||||
.elist = &ec_elist,
|
||||
.idxstack = &ec_idxstack,
|
||||
.ecaterror = &EcatError,
|
||||
.DCtime = &ec_DCtime,
|
||||
.SMcommtype = &ec_SMcommtype[0],
|
||||
.PDOassign = &ec_PDOassign[0],
|
||||
.PDOdesc = &ec_PDOdesc[0],
|
||||
.eepSM = &ec_SM,
|
||||
.eepFMMU = &ec_FMMU,
|
||||
.mbxpool = &ec_mbxpool,
|
||||
.FOEhook = NULL,
|
||||
.EOEhook = NULL,
|
||||
.manualstatechange = 0,
|
||||
.userdata = NULL,
|
||||
};
|
||||
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
@@ -52,28 +96,28 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
printf("Starting firmware update example\n");
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
if (ecx_init(&ctx, ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n", ifname);
|
||||
/* find and auto-config slaves */
|
||||
printf("ecx_init on %s succeeded.\n", ifname);
|
||||
|
||||
if (ec_config_init(FALSE) > 0)
|
||||
/* find and auto-config slaves */
|
||||
if (ecx_config_init(&ctx, FALSE) > 0)
|
||||
{
|
||||
printf("%d slaves found and configured.\n", ec_slavecount);
|
||||
|
||||
/* wait for all slaves to reach PRE_OP state */
|
||||
ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE * 4);
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE * 4);
|
||||
|
||||
printf("Request init state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_INIT;
|
||||
ec_writestate(slave);
|
||||
ecx_writestate(&ctx, slave);
|
||||
|
||||
/* wait for slave to reach INIT state */
|
||||
ec_statecheck(slave, EC_STATE_INIT, EC_TIMEOUTSTATE * 4);
|
||||
ecx_statecheck(&ctx, slave, EC_STATE_INIT, EC_TIMEOUTSTATE * 4);
|
||||
printf("Slave %d state to INIT.\n", slave);
|
||||
|
||||
/* read BOOT mailbox data, master -> slave */
|
||||
data = ec_readeeprom(slave, ECT_SII_BOOTRXMBX, EC_TIMEOUTEEP);
|
||||
data = ecx_readeeprom(&ctx, slave, ECT_SII_BOOTRXMBX, EC_TIMEOUTEEP);
|
||||
ec_slave[slave].SM[0].StartAddr = (uint16)LO_WORD(data);
|
||||
ec_slave[slave].SM[0].SMlength = (uint16)HI_WORD(data);
|
||||
/* store boot write mailbox address */
|
||||
@@ -82,7 +126,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
ec_slave[slave].mbx_l = (uint16)HI_WORD(data);
|
||||
|
||||
/* read BOOT mailbox data, slave -> master */
|
||||
data = ec_readeeprom(slave, ECT_SII_BOOTTXMBX, EC_TIMEOUTEEP);
|
||||
data = ecx_readeeprom(&ctx, slave, ECT_SII_BOOTTXMBX, EC_TIMEOUTEEP);
|
||||
ec_slave[slave].SM[1].StartAddr = (uint16)LO_WORD(data);
|
||||
ec_slave[slave].SM[1].SMlength = (uint16)HI_WORD(data);
|
||||
/* store boot read mailbox address */
|
||||
@@ -95,16 +139,16 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
printf(" SM1 A:%4.4x L:%4d F:%8.8x\n", ec_slave[slave].SM[1].StartAddr, ec_slave[slave].SM[1].SMlength,
|
||||
(int)ec_slave[slave].SM[1].SMflags);
|
||||
/* program SM0 mailbox in for slave */
|
||||
ec_FPWR(ec_slave[slave].configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
|
||||
ecx_FPWR(ctx.port, 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);
|
||||
ecx_FPWR(ctx.port, 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);
|
||||
ecx_writestate(&ctx, slave);
|
||||
|
||||
/* wait for slave to reach BOOT state */
|
||||
if (ec_statecheck(slave, EC_STATE_BOOT, EC_TIMEOUTSTATE * 10) == EC_STATE_BOOT)
|
||||
if (ecx_statecheck(&ctx, slave, EC_STATE_BOOT, EC_TIMEOUTSTATE * 10) == EC_STATE_BOOT)
|
||||
{
|
||||
printf("Slave %d state to BOOT.\n", slave);
|
||||
|
||||
@@ -112,11 +156,11 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
{
|
||||
printf("File read OK, %d bytes.\n", filesize);
|
||||
printf("FoE write....");
|
||||
j = ec_FOEwrite(slave, filename, 0, filesize, &filebuffer, EC_TIMEOUTSTATE);
|
||||
j = ecx_FOEwrite(&ctx, slave, filename, 0, filesize, &filebuffer, EC_TIMEOUTSTATE);
|
||||
printf("result %d.\n", j);
|
||||
printf("Request init state for slave %d\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_INIT;
|
||||
ec_writestate(slave);
|
||||
ecx_writestate(&ctx, slave);
|
||||
}
|
||||
else
|
||||
printf("File not read OK.\n");
|
||||
@@ -128,7 +172,7 @@ void boottest(char *ifname, uint16 slave, char *filename)
|
||||
}
|
||||
printf("End firmware update example, close socket\n");
|
||||
/* stop SOEM, close socket */
|
||||
ec_close();
|
||||
ecx_close(&ctx);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -147,11 +191,22 @@ int main(int argc, char *argv[])
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_adaptert *adapter = NULL;
|
||||
ec_adaptert *head = NULL;
|
||||
printf("Usage: firm_update ifname1 slave fname\n");
|
||||
printf("ifname = eth0 for example\n");
|
||||
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("\nAvailable adapters:\n");
|
||||
head = adapter = ec_find_adapters();
|
||||
while (adapter != NULL)
|
||||
{
|
||||
printf(" - %s (%s)\n", adapter->name, adapter->desc);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
ec_free_adapters(head);
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
3
samples/red_test/CMakeLists.txt
Normal file
3
samples/red_test/CMakeLists.txt
Normal file
@@ -0,0 +1,3 @@
|
||||
add_executable(red_test red_test.c)
|
||||
target_link_libraries(red_test soem)
|
||||
install(TARGETS red_test DESTINATION bin)
|
||||
@@ -11,39 +11,70 @@
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
#include <sched.h>
|
||||
#include <string.h>
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <pthread.h>
|
||||
#include <math.h>
|
||||
#include <stdlib.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include "ethercat.h"
|
||||
#include "soem/soem.h"
|
||||
|
||||
#define NSEC_PER_SEC 1000000000
|
||||
#define EC_TIMEOUTMON 500
|
||||
|
||||
struct sched_param schedp;
|
||||
char IOmap[4096];
|
||||
pthread_t thread1, thread2;
|
||||
struct timeval tv, t1, t2;
|
||||
int dorun = 0;
|
||||
int deltat, tmax = 0;
|
||||
int64 toff, gl_delta;
|
||||
int DCdiff;
|
||||
int os;
|
||||
uint8 ob;
|
||||
uint16 ob2;
|
||||
uint8 *digout = 0;
|
||||
OSAL_THREAD_HANDLE thread1;
|
||||
OSAL_THREAD_HANDLE thread2;
|
||||
int expectedWKC;
|
||||
boolean needlf;
|
||||
volatile int wkc;
|
||||
boolean inOP;
|
||||
uint8 currentgroup = 0;
|
||||
boolean forceByteAlignment = FALSE;
|
||||
uint8 *digout = NULL;
|
||||
int dorun = 0;
|
||||
int64 toff, gl_delta;
|
||||
|
||||
static ec_slavet ec_slave[EC_MAXSLAVE];
|
||||
static int ec_slavecount;
|
||||
static ec_groupt ec_group[EC_MAXGROUP];
|
||||
static uint8 ec_esibuf[EC_MAXEEPBUF];
|
||||
static uint32 ec_esimap[EC_MAXEEPBITMAP];
|
||||
static ec_eringt ec_elist;
|
||||
static ec_idxstackT ec_idxstack;
|
||||
static ec_SMcommtypet ec_SMcommtype[EC_MAX_MAPT];
|
||||
static ec_PDOassignt ec_PDOassign[EC_MAX_MAPT];
|
||||
static ec_PDOdesct ec_PDOdesc[EC_MAX_MAPT];
|
||||
static ec_eepromSMt ec_SM;
|
||||
static ec_eepromFMMUt ec_FMMU;
|
||||
static boolean EcatError = FALSE;
|
||||
static int64 ec_DCtime;
|
||||
static ecx_portt ecx_port;
|
||||
static ec_mbxpoolt ec_mbxpool;
|
||||
|
||||
static ecx_contextt ctx = {
|
||||
.port = &ecx_port,
|
||||
.slavelist = &ec_slave[0],
|
||||
.slavecount = &ec_slavecount,
|
||||
.maxslave = EC_MAXSLAVE,
|
||||
.grouplist = &ec_group[0],
|
||||
.maxgroup = EC_MAXGROUP,
|
||||
.esibuf = &ec_esibuf[0],
|
||||
.esimap = &ec_esimap[0],
|
||||
.esislave = 0,
|
||||
.elist = &ec_elist,
|
||||
.idxstack = &ec_idxstack,
|
||||
.ecaterror = &EcatError,
|
||||
.DCtime = &ec_DCtime,
|
||||
.SMcommtype = &ec_SMcommtype[0],
|
||||
.PDOassign = &ec_PDOassign[0],
|
||||
.PDOdesc = &ec_PDOdesc[0],
|
||||
.eepSM = &ec_SM,
|
||||
.eepFMMU = &ec_FMMU,
|
||||
.mbxpool = &ec_mbxpool,
|
||||
.FOEhook = NULL,
|
||||
.EOEhook = NULL,
|
||||
.manualstatechange = 0,
|
||||
.userdata = NULL,
|
||||
};
|
||||
|
||||
void redtest(char *ifname, char *ifname2)
|
||||
{
|
||||
@@ -53,22 +84,32 @@ void redtest(char *ifname, char *ifname2)
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
(void)ifname2;
|
||||
// if (ec_init_redundant(ifname, ifname2))
|
||||
if (ec_init(ifname))
|
||||
// if (ecx_init_redundant(&ctx, ifname, ifname2))
|
||||
if (ecx_init(&ctx, ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n", ifname);
|
||||
/* find and auto-config slaves */
|
||||
if (ec_config(FALSE, &IOmap) > 0)
|
||||
{
|
||||
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);
|
||||
printf("ecx_init on %s succeeded.\n", ifname);
|
||||
|
||||
/* configure DC options for every DC capable slave found in the list */
|
||||
ec_configdc();
|
||||
/* find and auto-config slaves */
|
||||
if (ecx_config_init(&ctx, FALSE) > 0)
|
||||
{
|
||||
if (forceByteAlignment)
|
||||
{
|
||||
ecx_config_map_group_aligned(&ctx, &IOmap, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
ecx_config_map_group(&ctx, &IOmap, 0);
|
||||
}
|
||||
|
||||
printf("%d slaves found and configured.\n", ec_slavecount);
|
||||
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
|
||||
|
||||
ecx_configdc(&ctx);
|
||||
|
||||
/* read indevidual slave state and store in ec_slave[] */
|
||||
ec_readstate();
|
||||
ecx_readstate(&ctx);
|
||||
for (cnt = 1; cnt <= ec_slavecount; cnt++)
|
||||
{
|
||||
printf("Slave:%d Name:%s Output size:%3dbits Input size:%3dbits State:%2d delay:%d.%d\n",
|
||||
@@ -88,11 +129,11 @@ void redtest(char *ifname, char *ifname2)
|
||||
printf("Request operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_OPERATIONAL;
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
ecx_writestate(&ctx, 0);
|
||||
/* activate cyclic process data */
|
||||
dorun = 1;
|
||||
/* wait for all slaves to reach OP state */
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
|
||||
oloop = ec_slave[0].Obytes;
|
||||
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
|
||||
if (oloop > 8) oloop = 8;
|
||||
@@ -127,7 +168,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
else
|
||||
{
|
||||
printf("Not all slaves reached operational state.\n");
|
||||
ec_readstate();
|
||||
ecx_readstate(&ctx);
|
||||
for (i = 1; i <= ec_slavecount; i++)
|
||||
{
|
||||
if (ec_slave[i].state != EC_STATE_OPERATIONAL)
|
||||
@@ -140,7 +181,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
printf("Request safe operational state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_SAFE_OP;
|
||||
/* request SAFE_OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
ecx_writestate(&ctx, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -148,7 +189,7 @@ void redtest(char *ifname, char *ifname2)
|
||||
}
|
||||
printf("End redundant test, close socket\n");
|
||||
/* stop SOEM, close socket */
|
||||
ec_close();
|
||||
ecx_close(&ctx);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -214,7 +255,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
cycletime = *(int *)ptr * 1000; /* cycletime in ns */
|
||||
toff = 0;
|
||||
dorun = 0;
|
||||
ec_send_processdata();
|
||||
ecx_send_processdata(&ctx);
|
||||
while (1)
|
||||
{
|
||||
/* calculate next cycle start */
|
||||
@@ -223,7 +264,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, &tleft);
|
||||
if (dorun > 0)
|
||||
{
|
||||
wkc = ec_receive_processdata(EC_TIMEOUTRET);
|
||||
wkc = ecx_receive_processdata(&ctx, EC_TIMEOUTRET);
|
||||
|
||||
dorun++;
|
||||
/* if we have some digital output, cycle */
|
||||
@@ -234,7 +275,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
/* calulate toff to get linux time and DC synced */
|
||||
ec_sync(ec_DCtime, cycletime, &toff);
|
||||
}
|
||||
ec_send_processdata();
|
||||
ecx_send_processdata(&ctx);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -242,8 +283,7 @@ OSAL_THREAD_FUNC_RT ecatthread(void *ptr)
|
||||
OSAL_THREAD_FUNC ecatcheck(void *ptr)
|
||||
{
|
||||
int slave;
|
||||
|
||||
(void)ptr;
|
||||
(void)ptr; /* Not used */
|
||||
|
||||
while (1)
|
||||
{
|
||||
@@ -256,7 +296,7 @@ OSAL_THREAD_FUNC ecatcheck(void *ptr)
|
||||
}
|
||||
/* one ore more slaves are not responding */
|
||||
ec_group[currentgroup].docheckstate = FALSE;
|
||||
ec_readstate();
|
||||
ecx_readstate(&ctx);
|
||||
for (slave = 1; slave <= ec_slavecount; slave++)
|
||||
{
|
||||
if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
|
||||
@@ -266,17 +306,18 @@ OSAL_THREAD_FUNC ecatcheck(void *ptr)
|
||||
{
|
||||
printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
|
||||
ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
|
||||
ec_writestate(slave);
|
||||
ecx_writestate(&ctx, slave);
|
||||
}
|
||||
else if (ec_slave[slave].state == EC_STATE_SAFE_OP)
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
if (ec_slave[slave].mbxhandlerstate == ECT_MBXH_LOST) ec_slave[slave].mbxhandlerstate = ECT_MBXH_CYCLIC;
|
||||
ecx_writestate(&ctx, slave);
|
||||
}
|
||||
else if (ec_slave[slave].state > EC_STATE_NONE)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
if (ecx_reconfig_slave(&ctx, slave, EC_TIMEOUTMON) >= EC_STATE_PRE_OP)
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n", slave);
|
||||
@@ -285,19 +326,26 @@ OSAL_THREAD_FUNC ecatcheck(void *ptr)
|
||||
else if (!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
|
||||
ecx_statecheck(&ctx, slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
|
||||
if (ec_slave[slave].state == EC_STATE_NONE)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
ec_slave[slave].mbxhandlerstate = ECT_MBXH_LOST;
|
||||
/* zero input data for this slave */
|
||||
if (ec_slave[slave].Ibytes)
|
||||
{
|
||||
memset(ec_slave[slave].inputs, 0x00, ec_slave[slave].Ibytes);
|
||||
printf("zero inputs %p %d\n\r", ec_slave[slave].inputs, ec_slave[slave].Ibytes);
|
||||
}
|
||||
printf("ERROR : slave %d lost\n", slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (ec_slave[slave].islost)
|
||||
{
|
||||
if (ec_slave[slave].state == EC_STATE_NONE)
|
||||
if (ec_slave[slave].state <= EC_STATE_INIT)
|
||||
{
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
if (ecx_recover_slave(&ctx, slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n", slave);
|
||||
@@ -317,8 +365,6 @@ OSAL_THREAD_FUNC ecatcheck(void *ptr)
|
||||
}
|
||||
}
|
||||
|
||||
#define stack64k (64 * 1024)
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
int ctime;
|
||||
@@ -331,17 +377,28 @@ int main(int argc, char *argv[])
|
||||
ctime = atoi(argv[3]);
|
||||
|
||||
/* create RT thread */
|
||||
osal_thread_create_rt(&thread1, stack64k * 2, &ecatthread, (void *)&ctime);
|
||||
osal_thread_create_rt(&thread1, 128000, &ecatthread, (void *)&ctime);
|
||||
|
||||
/* create thread to handle slave error handling in OP */
|
||||
osal_thread_create(&thread2, stack64k * 4, &ecatcheck, NULL);
|
||||
osal_thread_create(&thread2, 128000, &ecatcheck, NULL);
|
||||
|
||||
/* start acyclic part */
|
||||
redtest(argv[1], argv[2]);
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_adaptert *adapter = NULL;
|
||||
ec_adaptert *head = NULL;
|
||||
printf("Usage: red_test ifname1 ifname2 cycletime\nifname = eth0 for example\ncycletime in us\n");
|
||||
|
||||
printf("\nAvailable adapters:\n");
|
||||
head = adapter = ec_find_adapters();
|
||||
while (adapter != NULL)
|
||||
{
|
||||
printf(" - %s (%s)\n", adapter->name, adapter->desc);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
ec_free_adapters(head);
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
@@ -1,4 +1,3 @@
|
||||
set(SOURCES simple_ng.c)
|
||||
add_executable(simple_ng ${SOURCES})
|
||||
add_executable(simple_ng simple_ng.c)
|
||||
target_link_libraries(simple_ng soem)
|
||||
install(TARGETS simple_ng DESTINATION bin)
|
||||
|
||||
@@ -36,6 +36,7 @@ typedef struct
|
||||
ec_PDOdesct PDOdesc[EC_MAX_MAPT];
|
||||
ec_eepromSMt eepSM;
|
||||
ec_eepromFMMUt eepFMMU;
|
||||
ec_mbxpoolt mbxpool;
|
||||
} Fieldbus;
|
||||
|
||||
static void
|
||||
@@ -71,6 +72,7 @@ fieldbus_initialize(Fieldbus *fieldbus, char *iface)
|
||||
context->PDOdesc = fieldbus->PDOdesc;
|
||||
context->eepSM = &fieldbus->eepSM;
|
||||
context->eepFMMU = &fieldbus->eepFMMU;
|
||||
context->mbxpool = &fieldbus->mbxpool;
|
||||
context->FOEhook = NULL;
|
||||
context->EOEhook = NULL;
|
||||
context->manualstatechange = 0;
|
||||
|
||||
@@ -1,5 +1,3 @@
|
||||
|
||||
set(SOURCES simple_test.c)
|
||||
add_executable(simple_test ${SOURCES})
|
||||
add_executable(simple_test simple_test.c)
|
||||
target_link_libraries(simple_test soem)
|
||||
install(TARGETS simple_test DESTINATION bin)
|
||||
|
||||
@@ -80,13 +80,11 @@ void simpletest(char *ifname)
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ecx_init(&ctx, ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n", ifname);
|
||||
printf("ecx_init on %s succeeded.\n", ifname);
|
||||
|
||||
/* find and auto-config slaves */
|
||||
if (ecx_config_init(&ctx, FALSE) > 0)
|
||||
{
|
||||
printf("%d slaves found and configured.\n", ec_slavecount);
|
||||
|
||||
if (forceByteAlignment)
|
||||
{
|
||||
ecx_config_map_group_aligned(&ctx, &IOmap, 0);
|
||||
@@ -98,7 +96,8 @@ void simpletest(char *ifname)
|
||||
|
||||
ecx_configdc(&ctx);
|
||||
|
||||
printf("Slaves mapped, state to SAFE_OP.\n");
|
||||
printf("%d slaves found and configured.\n", ec_slavecount);
|
||||
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ecx_statecheck(&ctx, 0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 4);
|
||||
|
||||
|
||||
@@ -1,5 +1,3 @@
|
||||
|
||||
set(SOURCES slaveinfo.c)
|
||||
add_executable(slaveinfo ${SOURCES})
|
||||
add_executable(slaveinfo slaveinfo.c)
|
||||
target_link_libraries(slaveinfo soem)
|
||||
install(TARGETS slaveinfo DESTINATION bin)
|
||||
|
||||
@@ -646,13 +646,11 @@ void slaveinfo(char *ifname)
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ecx_init(&ctx, ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n", ifname);
|
||||
printf("ecx_init on %s succeeded.\n", ifname);
|
||||
|
||||
/* find and auto-config slaves */
|
||||
if (ecx_config_init(&ctx, FALSE) > 0)
|
||||
{
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
|
||||
if (forceByteAlignment)
|
||||
{
|
||||
ecx_config_map_group_aligned(&ctx, &IOmap, 0);
|
||||
@@ -779,11 +777,11 @@ int main(int argc, char *argv[])
|
||||
{
|
||||
printf("Usage: slaveinfo ifname [options]\nifname = eth0 for example\nOptions :\n -sdo : print SDO info\n -map : print mapping\n");
|
||||
|
||||
printf("Available adapters\n");
|
||||
printf("\nAvailable adapters:\n");
|
||||
head = adapter = ec_find_adapters();
|
||||
while (adapter != NULL)
|
||||
{
|
||||
printf("Description : %s, Device to use for wpcap: %s\n", adapter->desc, adapter->name);
|
||||
printf(" - %s (%s)\n", adapter->name, adapter->desc);
|
||||
adapter = adapter->next;
|
||||
}
|
||||
ec_free_adapters(head);
|
||||
|
||||
@@ -1,428 +0,0 @@
|
||||
/** \file
|
||||
* \brief EEprom tool for Simple Open EtherCAT master
|
||||
*
|
||||
* Usage : eepromtool ifname slave OPTION fname|alias
|
||||
* ifname is NIC interface, f.e. eth0
|
||||
* slave = slave number in EtherCAT order 1..n
|
||||
* -r read EEPROM, output binary format
|
||||
* -ri read EEPROM, output Intel Hex format
|
||||
* -w write EEPROM, input binary format
|
||||
* -wi write EEPROM, input Intel Hex format
|
||||
* -i display EEPROM information
|
||||
* -walias write slave alias in EEPROM
|
||||
*
|
||||
* (c)Arthur Ketels 2010-2012
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
#include <time.h>
|
||||
|
||||
#include "ethercat.h"
|
||||
|
||||
#define MAXBUF 32768
|
||||
#define STDBUF 2048
|
||||
#define MINBUF 128
|
||||
|
||||
#define MODE_NONE 0
|
||||
#define MODE_READBIN 1
|
||||
#define MODE_READINTEL 2
|
||||
#define MODE_WRITEBIN 3
|
||||
#define MODE_WRITEINTEL 4
|
||||
#define MODE_WRITEALIAS 5
|
||||
#define MODE_INFO 6
|
||||
|
||||
#define MAXSLENGTH 256
|
||||
|
||||
uint8 ebuf[MAXBUF];
|
||||
uint8 ob;
|
||||
uint16 ow;
|
||||
int os;
|
||||
int slave;
|
||||
int alias;
|
||||
struct timeval tstart, tend, tdif;
|
||||
int wkc;
|
||||
int mode;
|
||||
char sline[MAXSLENGTH];
|
||||
|
||||
#define IHEXLENGTH 0x20
|
||||
|
||||
int input_bin(char *fname, int *length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
int cc = 0, c;
|
||||
|
||||
fp = fopen(fname, "rb");
|
||||
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)
|
||||
return 0;
|
||||
hstart = MAXBUF;
|
||||
hlength = 0;
|
||||
sum = 0;
|
||||
do
|
||||
{
|
||||
memset(sline, 0x00, MAXSLENGTH);
|
||||
sc = 0;
|
||||
while (((c = fgetc(fp)) != EOF) && (c != 0x0A) && (sc < (MAXSLENGTH - 1)))
|
||||
sline[sc++] = (uint8)c;
|
||||
if ((c != EOF) && ((sc < 11) || (sline[0] != ':')))
|
||||
{
|
||||
c = EOF;
|
||||
retval = 0;
|
||||
printf("Invalid Intel Hex format.\n");
|
||||
}
|
||||
if (c != EOF)
|
||||
{
|
||||
sn = sscanf(sline, ":%2x%4x%2x", &ll, &ladr, <);
|
||||
if ((sn == 3) && ((ladr + ll) <= MAXBUF) && (lt == 0))
|
||||
{
|
||||
sum = ll + (ladr >> 8) + (ladr & 0xff) + lt;
|
||||
if (ladr < hstart) hstart = ladr;
|
||||
for (i = 0; i < ll; i++)
|
||||
{
|
||||
sn = sscanf(&sline[9 + (i << 1)], "%2x", &lval);
|
||||
ebuf[ladr + i] = (uint8)lval;
|
||||
sum += (uint8)lval;
|
||||
}
|
||||
if (((ladr + ll) - hstart) > hlength)
|
||||
hlength = (ladr + ll) - hstart;
|
||||
sum = (0x100 - sum) & 0xff;
|
||||
sn = sscanf(&sline[9 + (i << 1)], "%2x", &lval);
|
||||
if (!sn || ((sum - lval) != 0))
|
||||
{
|
||||
c = EOF;
|
||||
retval = 0;
|
||||
printf("Invalid checksum.\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
} while (c != EOF);
|
||||
if (retval)
|
||||
{
|
||||
*length = hlength;
|
||||
*start = hstart;
|
||||
}
|
||||
fclose(fp);
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
int output_bin(char *fname, int length)
|
||||
{
|
||||
FILE *fp;
|
||||
|
||||
int cc;
|
||||
|
||||
fp = fopen(fname, "wb");
|
||||
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)
|
||||
return 0;
|
||||
while (cc < length)
|
||||
{
|
||||
ll = length - cc;
|
||||
if (ll > IHEXLENGTH) ll = IHEXLENGTH;
|
||||
sum = ll + (cc >> 8) + (cc & 0xff);
|
||||
fprintf(fp, ":%2.2X%4.4X00", ll, cc);
|
||||
for (i = 0; i < ll; i++)
|
||||
{
|
||||
fprintf(fp, "%2.2X", ebuf[cc + i]);
|
||||
sum += ebuf[cc + i];
|
||||
}
|
||||
fprintf(fp, "%2.2X\n", (0x100 - sum) & 0xff);
|
||||
cc += ll;
|
||||
}
|
||||
fprintf(fp, ":00000001FF\n");
|
||||
fclose(fp);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int eeprom_read(int slave, int start, int length)
|
||||
{
|
||||
int i, wkc, ainc = 4;
|
||||
uint16 estat, aiadr;
|
||||
uint32 b4;
|
||||
uint64 b8;
|
||||
uint8 eepctl;
|
||||
|
||||
if ((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
eepctl = 2;
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl, EC_TIMEOUTRET); /* force Eeprom from PDI */
|
||||
eepctl = 0;
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl, EC_TIMEOUTRET); /* set Eeprom to master */
|
||||
|
||||
estat = 0x0000;
|
||||
aiadr = 1 - slave;
|
||||
wkc = ec_APRD(aiadr, ECT_REG_EEPSTAT, sizeof(estat), &estat, EC_TIMEOUTRET); /* read eeprom status */
|
||||
estat = etohs(estat);
|
||||
if (estat & EC_ESTAT_R64)
|
||||
{
|
||||
ainc = 8;
|
||||
for (i = start; i < (start + length); i += ainc)
|
||||
{
|
||||
b8 = ec_readeepromAP(aiadr, i >> 1, EC_TIMEOUTEEP);
|
||||
ebuf[i] = b8;
|
||||
ebuf[i + 1] = b8 >> 8;
|
||||
ebuf[i + 2] = b8 >> 16;
|
||||
ebuf[i + 3] = b8 >> 24;
|
||||
ebuf[i + 4] = b8 >> 32;
|
||||
ebuf[i + 5] = b8 >> 40;
|
||||
ebuf[i + 6] = b8 >> 48;
|
||||
ebuf[i + 7] = b8 >> 56;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
for (i = start; i < (start + length); i += ainc)
|
||||
{
|
||||
b4 = ec_readeepromAP(aiadr, i >> 1, EC_TIMEOUTEEP);
|
||||
ebuf[i] = b4;
|
||||
ebuf[i + 1] = b4 >> 8;
|
||||
ebuf[i + 2] = b4 >> 16;
|
||||
ebuf[i + 3] = b4 >> 24;
|
||||
}
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int eeprom_write(int slave, int start, int length)
|
||||
{
|
||||
int i, wkc, dc = 0;
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
if ((ec_slavecount >= slave) && (slave > 0) && ((start + length) <= MAXBUF))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
eepctl = 2;
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl, EC_TIMEOUTRET); /* force Eeprom from PDI */
|
||||
eepctl = 0;
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl, EC_TIMEOUTRET); /* set Eeprom to master */
|
||||
|
||||
aiadr = 1 - slave;
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
for (i = start; i < (start + length); i += 2)
|
||||
{
|
||||
ret = ec_writeeepromAP(aiadr, i >> 1, *(wbuf + (i >> 1)), EC_TIMEOUTEEP);
|
||||
if (++dc >= 100)
|
||||
{
|
||||
dc = 0;
|
||||
printf(".");
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int eeprom_writealias(int slave, int alias)
|
||||
{
|
||||
int i, wkc, dc = 0;
|
||||
uint16 aiadr, *wbuf;
|
||||
uint8 eepctl;
|
||||
int ret;
|
||||
|
||||
if ((ec_slavecount >= slave) && (slave > 0) && (alias <= 0xffff))
|
||||
{
|
||||
aiadr = 1 - slave;
|
||||
eepctl = 2;
|
||||
wkc = ec_APWR(aiadr, ECT_REG_EEPCFG, sizeof(eepctl), &eepctl, EC_TIMEOUTRET); /* force Eeprom from PDI */
|
||||
eepctl = 0;
|
||||
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;
|
||||
}
|
||||
|
||||
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;
|
||||
wkc = ec_BRD(0x0000, ECT_REG_TYPE, sizeof(w), &w, EC_TIMEOUTSAFE); /* detect number of slaves */
|
||||
if (wkc > 0)
|
||||
{
|
||||
ec_slavecount = wkc;
|
||||
|
||||
printf("%d slaves found.\n", ec_slavecount);
|
||||
if ((ec_slavecount >= slave) && (slave > 0))
|
||||
{
|
||||
if ((mode == MODE_INFO) || (mode == MODE_READBIN) || (mode == MODE_READINTEL))
|
||||
{
|
||||
rc = gettimeofday(&tstart, NULL);
|
||||
eeprom_read(slave, 0x0000, MINBUF); // read first 128 bytes
|
||||
|
||||
wbuf = (uint16 *)&ebuf[0];
|
||||
printf("Slave %d data\n", slave);
|
||||
printf(" PDI Control : %4.4X\n", *(wbuf + 0x00));
|
||||
printf(" PDI Config : %4.4X\n", *(wbuf + 0x01));
|
||||
printf(" Config Alias : %4.4X\n", *(wbuf + 0x04));
|
||||
printf(" Checksum : %4.4X\n", *(wbuf + 0x07));
|
||||
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));
|
||||
printf(" Serial Number : %8.8X\n", *(uint32 *)(wbuf + 0x0E));
|
||||
printf(" Mailbox Protocol : %4.4X\n", *(wbuf + 0x1C));
|
||||
esize = (*(wbuf + 0x3E) + 1) * 128;
|
||||
if (esize > MAXBUF) esize = MAXBUF;
|
||||
printf(" Size : %4.4X = %d bytes\n", *(wbuf + 0x3E), esize);
|
||||
printf(" Version : %4.4X\n", *(wbuf + 0x3F));
|
||||
}
|
||||
if ((mode == MODE_READBIN) || (mode == MODE_READINTEL))
|
||||
{
|
||||
if (esize > MINBUF)
|
||||
eeprom_read(slave, MINBUF, esize - MINBUF); // read reminder
|
||||
|
||||
rc = gettimeofday(&tend, NULL);
|
||||
timersub(&tend, &tstart, &tdif);
|
||||
if (mode == MODE_READINTEL) output_intelhex(fname, esize);
|
||||
if (mode == MODE_READBIN) output_bin(fname, esize);
|
||||
|
||||
printf("\nTotal EEPROM read time :%ldms\n", (tdif.tv_usec + (tdif.tv_sec * 1000000L)) / 1000);
|
||||
}
|
||||
if ((mode == MODE_WRITEBIN) || (mode == MODE_WRITEINTEL))
|
||||
{
|
||||
estart = 0;
|
||||
if (mode == MODE_WRITEINTEL) rc = input_intelhex(fname, &estart, &esize);
|
||||
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));
|
||||
printf(" Product Code : %8.8X\n", *(uint32 *)(wbuf + 0x0A));
|
||||
printf(" Revision Number : %8.8X\n", *(uint32 *)(wbuf + 0x0C));
|
||||
printf(" Serial Number : %8.8X\n", *(uint32 *)(wbuf + 0x0E));
|
||||
|
||||
printf("Busy");
|
||||
fflush(stdout);
|
||||
rc = gettimeofday(&tstart, NULL);
|
||||
eeprom_write(slave, estart, esize);
|
||||
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");
|
||||
}
|
||||
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");
|
||||
}
|
||||
}
|
||||
else
|
||||
printf("Slave number outside range.\n");
|
||||
}
|
||||
else
|
||||
printf("No slaves found!\n");
|
||||
printf("End, close socket\n");
|
||||
/* stop SOEM, close socket */
|
||||
ec_close();
|
||||
}
|
||||
else
|
||||
printf("No socket connection on %s\nExcecute as root\n", ifname);
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nEEPROM tool\n");
|
||||
|
||||
mode = MODE_NONE;
|
||||
if (argc > 3)
|
||||
{
|
||||
slave = atoi(argv[2]);
|
||||
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;
|
||||
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;
|
||||
if ((strncmp(argv[3], "-walias", sizeof("-walias")) == 0))
|
||||
{
|
||||
mode = MODE_WRITEALIAS;
|
||||
alias = atoi(argv[4]);
|
||||
}
|
||||
}
|
||||
/* start tool */
|
||||
eepromtool(argv[1], slave, mode, argv[4]);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Usage: eepromtool ifname slave OPTION fname|alias\n");
|
||||
printf("ifname = eth0 for example\n");
|
||||
printf("slave = slave number in EtherCAT order 1..n\n");
|
||||
printf(" -i display EEPROM information\n");
|
||||
printf(" -walias write slave alias\n");
|
||||
printf(" -r read EEPROM, output binary format\n");
|
||||
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);
|
||||
}
|
||||
@@ -1,3 +0,0 @@
|
||||
set(SOURCES coetest.c)
|
||||
add_executable(coetest ${SOURCES})
|
||||
target_link_libraries(coetest soem)
|
||||
Reference in New Issue
Block a user