Merge d6767b8c72
into 6501580d9e
commit
7ed372c9cf
|
@ -0,0 +1,5 @@
|
|||
test
|
||||
lib
|
||||
osal/linux/obj
|
||||
oshw/linux/obj
|
||||
soem/obj
|
|
@ -42,6 +42,11 @@
|
|||
#ifndef _osal_defs_
|
||||
#define _osal_defs_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
|
@ -53,4 +58,8 @@
|
|||
#define OSAL_THREAD_FUNC void
|
||||
#define OSAL_THREAD_FUNC_RT void
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,6 +21,11 @@
|
|||
#ifndef _osal_
|
||||
#define _osal_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <osal_defs.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
@ -58,4 +63,8 @@ void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff);
|
|||
int osal_thread_create(void *thandle, int stacksize, void *func, void *param);
|
||||
int osal_thread_create_rt(void *thandle, int stacksize, void *func, void *param);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -45,11 +45,11 @@
|
|||
*
|
||||
* 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 allways return in the receive buffer.
|
||||
* 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 recieved.
|
||||
* 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.
|
||||
*
|
||||
|
@ -62,7 +62,7 @@
|
|||
* 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 resend through interface B.
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer if fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
|
@ -210,7 +210,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port stuct available? */
|
||||
/* secondary port struct available? */
|
||||
if (port->redport)
|
||||
{
|
||||
/* when using secondary socket it is automatically a redundant setup */
|
||||
|
@ -283,8 +283,8 @@ int ecx_closenic(ecx_portt *port)
|
|||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is allways broadcast.
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
|
|
|
@ -45,11 +45,11 @@
|
|||
*
|
||||
* 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 allways return in the receive buffer.
|
||||
* 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 recieved.
|
||||
* 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.
|
||||
*
|
||||
|
@ -62,7 +62,7 @@
|
|||
* 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 resend through interface B.
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer if fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
|
@ -135,7 +135,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
rval = 0;
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port stuct available? */
|
||||
/* secondary port struct available? */
|
||||
if (port->redport)
|
||||
{
|
||||
/* when using secondary socket it is automatically a redundant setup */
|
||||
|
@ -227,8 +227,8 @@ int ecx_closenic(ecx_portt *port)
|
|||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is allways broadcast.
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
|
|
|
@ -47,6 +47,11 @@
|
|||
#ifndef _oshw_
|
||||
#define _oshw_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include "ethercattype.h"
|
||||
#include "nicdrv.h"
|
||||
#include "ethercatmain.h"
|
||||
|
@ -56,4 +61,8 @@ uint16 oshw_ntohs(uint16 networkshort);
|
|||
ec_adaptert * oshw_find_adapters(void);
|
||||
void oshw_free_adapters(ec_adaptert * adapter);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -45,11 +45,11 @@
|
|||
*
|
||||
* 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 allways return in the receive buffer.
|
||||
* 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 recieved.
|
||||
* 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.
|
||||
*
|
||||
|
@ -62,7 +62,7 @@
|
|||
* 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 resend through interface B.
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer is fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
|
@ -137,7 +137,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port stuct available? */
|
||||
/* secondary port struct available? */
|
||||
if (port->redport)
|
||||
{
|
||||
/* when using secondary socket it is automatically a redundant setup */
|
||||
|
@ -207,8 +207,8 @@ int ecx_closenic(ecx_portt *port)
|
|||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is allways broadcast.
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
|
|
|
@ -45,11 +45,11 @@
|
|||
*
|
||||
* 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 allways return in the receive buffer.
|
||||
* 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 recieved.
|
||||
* 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.
|
||||
*
|
||||
|
@ -62,7 +62,7 @@
|
|||
* 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 resend through interface B.
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer is fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
|
@ -131,7 +131,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
rval = 0;
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port stuct available? */
|
||||
/* secondary port struct available? */
|
||||
if (port->redport)
|
||||
{
|
||||
/* when using secondary socket it is automatically a redundant setup */
|
||||
|
@ -217,8 +217,8 @@ int ecx_closenic(ecx_portt *port)
|
|||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is allways broadcast.
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
|
|
|
@ -51,6 +51,11 @@
|
|||
#ifndef _ethercatconfiglist_
|
||||
#define _ethercatconfiglist_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/*
|
||||
explanation of dev:
|
||||
1: static device with no IO mapping ie EK1100
|
||||
|
@ -90,4 +95,8 @@ ec_configlist_t ec_configlist[] = {
|
|||
{/*Man=*/EC_CONFIGEND,/*ID=*/0x00000000,/*Name=*/"" ,/*dtype=*/0,/*Ibits=*/ 0,/*Obits=*/ 0,/*SM2a*/ 0,/*SM2f*/ 0,/*SM3a*/ 0,/*SM3f*/ 0,/*FM0ac*/0,/*FM1ac*/0}
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1900,7 +1900,7 @@ void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode)
|
|||
ecx_packeterror(&ecx_context, Slave, Index, SubIdx, ErrorCode);
|
||||
}
|
||||
|
||||
int ec_init(char * ifname)
|
||||
int ec_init(const char * ifname)
|
||||
{
|
||||
return ecx_init(&ecx_context, ifname);
|
||||
}
|
||||
|
|
|
@ -53,7 +53,7 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
/** max. etries in EtherCAT error list */
|
||||
/** max. entries in EtherCAT error list */
|
||||
#define EC_MAXELIST 64
|
||||
/** max. length of readable name in slavelist and Object Description List */
|
||||
#define EC_MAXNAME 40
|
||||
|
@ -197,7 +197,7 @@ typedef struct
|
|||
uint16 mbx_proto;
|
||||
/** Counter value of mailbox link layer protocol 1..7 */
|
||||
uint8 mbx_cnt;
|
||||
/** has DC capabillity */
|
||||
/** has DC capability */
|
||||
boolean hasdc;
|
||||
/** Physical type; Ebus, EtherNet combinations */
|
||||
uint8 ptype;
|
||||
|
@ -473,7 +473,7 @@ void ec_pusherror(const ec_errort *Ec);
|
|||
boolean ec_poperror(ec_errort *Ec);
|
||||
boolean ec_iserror(void);
|
||||
void ec_packeterror(uint16 Slave, uint16 Index, uint8 SubIdx, uint16 ErrorCode);
|
||||
int ec_init(char * ifname);
|
||||
int ec_init(const char * ifname);
|
||||
int ec_init_redundant(char *ifname, char *if2name);
|
||||
void ec_close(void);
|
||||
uint8 ec_siigetbyte(uint16 slave, uint16 address);
|
||||
|
|
|
@ -0,0 +1,544 @@
|
|||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatsi.c
|
||||
* Version : 1.3.1
|
||||
* Date : 2015-04-16
|
||||
* Copyright (C) 2005-2015 Speciaal Machinefabriek Ketels v.o.f.
|
||||
* Copyright (C) 2005-2015 Arthur Ketels
|
||||
* Copyright (C) 2008-2009 TU/e Technische Universiteit Eindhoven
|
||||
* Copyright (C) 2014-2015 rt-labs AB , Sweden
|
||||
*
|
||||
* SOEM is free software; you can redistribute it and/or modify it under
|
||||
* the terms of the GNU General Public License version 2 as published by the Free
|
||||
* Software Foundation.
|
||||
*
|
||||
* SOEM 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.
|
||||
*
|
||||
* As a special exception, if other files instantiate templates or use macros
|
||||
* or inline functions from this file, or you compile this file and link it
|
||||
* with other works to produce a work based on this file, this file does not
|
||||
* by itself cause the resulting work to be covered by the GNU General Public
|
||||
* License. However the source code for this file must still be made available
|
||||
* in accordance with section (3) of the GNU General Public License.
|
||||
*
|
||||
* This exception does not invalidate any other reasons why a work based on
|
||||
* this file might be covered by the GNU General Public License.
|
||||
*
|
||||
* The EtherCAT Technology, the trade name and logo “EtherCAT” are the intellectual
|
||||
* property of, and protected by Beckhoff Automation GmbH. You can use SOEM for
|
||||
* the sole purpose of creating, using and/or selling or otherwise distributing
|
||||
* an EtherCAT network master provided that an EtherCAT Master License is obtained
|
||||
* from Beckhoff Automation GmbH.
|
||||
*
|
||||
* In case you did not receive a copy of the EtherCAT Master License along with
|
||||
* SOEM write to Beckhoff Automation GmbH, Eiserstraße 5, D-33415 Verl, Germany
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
/**
|
||||
* \file
|
||||
* \brief
|
||||
* Main EtherCAT slave info functions.
|
||||
*
|
||||
*/
|
||||
#include "ethercatsi.h"
|
||||
|
||||
char hstr[1024];
|
||||
ec_ODlistt ODlist;
|
||||
ec_OElistt OElist;
|
||||
|
||||
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)
|
||||
{
|
||||
char usdo[128];
|
||||
|
||||
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.16llx %lld", *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.16llx %llu", *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, uint8_t* IOmap)
|
||||
{
|
||||
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 - IOmap), 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 - IOmap), 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;
|
||||
|
||||
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, uint8_t* IOmap)
|
||||
{
|
||||
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 */
|
||||
printf("si_map_sii: slave: %d\n", slave);
|
||||
printf("si_map_sii: ec_slave[slave].outputs: %p\n", ec_slave[slave].outputs);
|
||||
printf("si_map_sii: IOmap: %p\n", IOmap);
|
||||
printf("si_map_sii: outputs_bo: %d\n", outputs_bo);
|
||||
|
||||
Tsize = si_siiPDO(slave, 1, (int)(ec_slave[slave].outputs - (uint8_t*)IOmap), outputs_bo );
|
||||
outputs_bo += Tsize;
|
||||
|
||||
|
||||
/* read the assign TXPDOs */
|
||||
printf("si_map_sii: slave: %d\n", slave);
|
||||
printf("si_map_sii: ec_slave[slave].inputs: %p\n", ec_slave[slave].inputs);
|
||||
printf("si_map_sii: IOmap: %p\n", IOmap);
|
||||
printf("si_map_sii: inputs_bo: %d\n", inputs_bo);
|
||||
|
||||
|
||||
Tsize = si_siiPDO(slave, 0, (int)(ec_slave[slave].inputs - (uint8_t*)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());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,81 @@
|
|||
/*
|
||||
* Simple Open EtherCAT Master Library
|
||||
*
|
||||
* File : ethercatsi.h
|
||||
* Version : 1.3.1
|
||||
* Date : 2015-04-16
|
||||
* Copyright (C) 2005-2015 Speciaal Machinefabriek Ketels v.o.f.
|
||||
* Copyright (C) 2005-2015 Arthur Ketels
|
||||
* Copyright (C) 2008-2009 TU/e Technische Universiteit Eindhoven
|
||||
* Copyright (C) 2014-2015 rt-labs AB , Sweden
|
||||
*
|
||||
* SOEM is free software; you can redistribute it and/or modify it under
|
||||
* the terms of the GNU General Public License version 2 as published by the Free
|
||||
* Software Foundation.
|
||||
*
|
||||
* SOEM 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.
|
||||
*
|
||||
* As a special exception, if other files instantiate templates or use macros
|
||||
* or inline functions from this file, or you compile this file and link it
|
||||
* with other works to produce a work based on this file, this file does not
|
||||
* by itself cause the resulting work to be covered by the GNU General Public
|
||||
* License. However the source code for this file must still be made available
|
||||
* in accordance with section (3) of the GNU General Public License.
|
||||
*
|
||||
* This exception does not invalidate any other reasons why a work based on
|
||||
* this file might be covered by the GNU General Public License.
|
||||
*
|
||||
* The EtherCAT Technology, the trade name and logo <EFBFBD>EtherCAT<EFBFBD> are the intellectual
|
||||
* property of, and protected by Beckhoff Automation GmbH. You can use SOEM for
|
||||
* the sole purpose of creating, using and/or selling or otherwise distributing
|
||||
* an EtherCAT network master provided that an EtherCAT Master License is obtained
|
||||
* from Beckhoff Automation GmbH.
|
||||
*
|
||||
* In case you did not receive a copy of the EtherCAT Master License along with
|
||||
* SOEM write to Beckhoff Automation GmbH, Eiserstra<EFBFBD>e 5, D-33415 Verl, Germany
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
||||
#ifndef _ethercatsi_
|
||||
#define _ethercatsi_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include "osal.h"
|
||||
#include "oshw.h"
|
||||
#include "ethercattype.h"
|
||||
#include "ethercatbase.h"
|
||||
#include "ethercatmain.h"
|
||||
#include "ethercatcoe.h"
|
||||
#include "ethercatprint.h"
|
||||
#include "ethercatsi.h"
|
||||
|
||||
// 'public'
|
||||
int si_map_sii(int slave, uint8_t* IOmap);
|
||||
|
||||
void si_sdo(int cnt);
|
||||
|
||||
// 'private'
|
||||
char* dtype2string(uint16 dtype);
|
||||
|
||||
char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype);
|
||||
|
||||
int si_PDOassign(uint16 slave, uint16 PDOassign, int mapoffset, int bitoffset);
|
||||
|
||||
int si_map_sdo(int slave, uint8_t* IOmap);
|
||||
|
||||
int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // _ethercatsi_
|
|
@ -43,10 +43,10 @@
|
|||
* \brief
|
||||
* General typedefs and defines for EtherCAT.
|
||||
*
|
||||
* Defines that could need optimalisation for specific applications
|
||||
* Defines that could need optimisation for specific applications
|
||||
* are the EC_TIMEOUTxxx. Assumptions for the standard settings are a
|
||||
* standard linux PC or laptop and a wired connection to maximal 100 slaves.
|
||||
* For use with wireless connections or lots of slaves the timouts need
|
||||
* For use with wireless connections or lots of slaves the timeouts need
|
||||
* increasing. For fast systems running Xenomai and RT-net or alike the
|
||||
* timeouts need to be shorter.
|
||||
*/
|
||||
|
@ -168,7 +168,7 @@ typedef enum
|
|||
EC_ERR_ALREADY_INITIALIZED,
|
||||
/** Library not initialized. */
|
||||
EC_ERR_NOT_INITIALIZED,
|
||||
/** Timeout occured during execution of the function. */
|
||||
/** Timeout occurred during execution of the function. */
|
||||
EC_ERR_TIMEOUT,
|
||||
/** No slaves were found. */
|
||||
EC_ERR_NO_SLAVES,
|
||||
|
@ -260,7 +260,7 @@ typedef enum
|
|||
EC_CMD_FPRW,
|
||||
/** Broadcast Read */
|
||||
EC_CMD_BRD,
|
||||
/** Broaddcast Write */
|
||||
/** Broadcast Write */
|
||||
EC_CMD_BWR,
|
||||
/** Broadcast Read Write */
|
||||
EC_CMD_BRW,
|
||||
|
@ -270,9 +270,9 @@ typedef enum
|
|||
EC_CMD_LWR,
|
||||
/** Logical Memory Read Write */
|
||||
EC_CMD_LRW,
|
||||
/** Auto Increment Read Mulitple Write */
|
||||
/** Auto Increment Read Multiple Write */
|
||||
EC_CMD_ARMW,
|
||||
/** Configured Read Mulitple Write */
|
||||
/** Configured Read Multiple Write */
|
||||
EC_CMD_FRMW
|
||||
/** Reserved */
|
||||
} ec_cmdtype;
|
||||
|
|
|
@ -598,11 +598,11 @@ void slaveinfo(char *ifname)
|
|||
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 & 0x04) && printSDO)
|
||||
if ((ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE) && printSDO)
|
||||
si_sdo(cnt);
|
||||
if(printMAP)
|
||||
{
|
||||
if (ec_slave[cnt].mbx_proto & 0x04)
|
||||
if (ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE)
|
||||
si_map_sdo(cnt);
|
||||
else
|
||||
si_map_sii(cnt);
|
||||
|
|
|
@ -594,11 +594,11 @@ void slaveinfo(char *ifname)
|
|||
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 & 0x04) && printSDO)
|
||||
if ((ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE) && printSDO)
|
||||
si_sdo(cnt);
|
||||
if(printMAP)
|
||||
{
|
||||
if (ec_slave[cnt].mbx_proto & 0x04)
|
||||
if (ec_slave[cnt].mbx_proto & ECT_MBXPROT_COE)
|
||||
si_map_sdo(cnt);
|
||||
else
|
||||
si_map_sii(cnt);
|
||||
|
|
Loading…
Reference in New Issue