Make PDO CA access thread safe (#51)
This commit is contained in:
parent
43e4493346
commit
03601959b6
|
@ -769,39 +769,43 @@ int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
|||
/** Read PDO assign structure in Complete Access mode
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Thread_n = Calling thread index
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
*/
|
||||
int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, int Thread_n,
|
||||
uint16 PDOassign)
|
||||
{
|
||||
uint16 idxloop, nidx, subidxloop, idx, subidx;
|
||||
int wkc, bsize = 0, rdl;
|
||||
|
||||
/* find maximum size of PDOassign buffer */
|
||||
rdl = sizeof(ec_PDOassignt);
|
||||
context->PDOassign->n=0;
|
||||
context->PDOassign[Thread_n].n=0;
|
||||
/* read rxPDOassign in CA mode, all subindexes are read in one struct */
|
||||
wkc = ecx_SDOread(context, Slave, PDOassign, 0x00, TRUE, &rdl, context->PDOassign, EC_TIMEOUTRXM);
|
||||
wkc = ecx_SDOread(context, Slave, PDOassign, 0x00, TRUE, &rdl,
|
||||
&(context->PDOassign[Thread_n]), EC_TIMEOUTRXM);
|
||||
/* positive result from slave ? */
|
||||
if ((wkc > 0) && (context->PDOassign->n > 0))
|
||||
if ((wkc > 0) && (context->PDOassign[Thread_n].n > 0))
|
||||
{
|
||||
nidx = context->PDOassign->n;
|
||||
nidx = context->PDOassign[Thread_n].n;
|
||||
bsize = 0;
|
||||
/* for each PDO do */
|
||||
for (idxloop = 1; idxloop <= nidx; idxloop++)
|
||||
{
|
||||
/* get index from PDOassign struct */
|
||||
idx = etohs(context->PDOassign->index[idxloop - 1]);
|
||||
idx = etohs(context->PDOassign[Thread_n].index[idxloop - 1]);
|
||||
if (idx > 0)
|
||||
{
|
||||
rdl = sizeof(ec_PDOdesct); context->PDOdesc->n = 0;
|
||||
rdl = sizeof(ec_PDOdesct); context->PDOdesc[Thread_n].n = 0;
|
||||
/* read SDO's that are mapped in PDO, CA mode */
|
||||
wkc = ecx_SDOread(context, Slave,idx, 0x00, TRUE, &rdl, context->PDOdesc, EC_TIMEOUTRXM);
|
||||
subidx = context->PDOdesc->n;
|
||||
wkc = ecx_SDOread(context, Slave,idx, 0x00, TRUE, &rdl,
|
||||
&(context->PDOdesc[Thread_n]), EC_TIMEOUTRXM);
|
||||
subidx = context->PDOdesc[Thread_n].n;
|
||||
/* extract all bitlengths of SDO's */
|
||||
for (subidxloop = 1; subidxloop <= subidx; subidxloop++)
|
||||
{
|
||||
bsize += LO_BYTE(etohl(context->PDOdesc->PDO[subidxloop -1]));
|
||||
bsize += LO_BYTE(etohl(context->PDOdesc[Thread_n].PDO[subidxloop -1]));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -932,13 +936,14 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
|||
* tries to read them and collect a full input and output mapping size
|
||||
* of designated slave. Slave has to support CA, otherwise use ec_readPDOmap().
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @param[in] context = context struct
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Thread_n = Calling thread index
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
*/
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, int *Osize, int *Isize)
|
||||
{
|
||||
int wkc, rdl;
|
||||
int retVal = 0;
|
||||
|
@ -950,13 +955,14 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
|||
*Osize = 0;
|
||||
SMt_bug_add = 0;
|
||||
rdl = sizeof(ec_SMcommtypet);
|
||||
context->SMcommtype->n = 0;
|
||||
context->SMcommtype[Thread_n].n = 0;
|
||||
/* read SyncManager Communication Type object count Complete Access*/
|
||||
wkc = ecx_SDOread(context, Slave, ECT_SDO_SMCOMMTYPE, 0x00, TRUE, &rdl, context->SMcommtype, EC_TIMEOUTRXM);
|
||||
wkc = ecx_SDOread(context, Slave, ECT_SDO_SMCOMMTYPE, 0x00, TRUE, &rdl,
|
||||
&(context->SMcommtype[Thread_n]), EC_TIMEOUTRXM);
|
||||
/* positive result from slave ? */
|
||||
if ((wkc > 0) && (context->SMcommtype->n > 2))
|
||||
if ((wkc > 0) && (context->SMcommtype[Thread_n].n > 2))
|
||||
{
|
||||
nSM = context->SMcommtype->n;
|
||||
nSM = context->SMcommtype[Thread_n].n;
|
||||
/* limit to maximum number of SM defined, if true the slave can't be configured */
|
||||
if (nSM > EC_MAXSM)
|
||||
{
|
||||
|
@ -966,7 +972,7 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
|||
/* iterate for every SM type defined */
|
||||
for (iSM = 2 ; iSM < nSM ; iSM++)
|
||||
{
|
||||
tSM = context->SMcommtype->SMtype[iSM];
|
||||
tSM = context->SMcommtype[Thread_n].SMtype[iSM];
|
||||
|
||||
// start slave bug prevention code, remove if possible
|
||||
if((iSM == 2) && (tSM == 2)) // SM2 has type 2 == mailbox out, this is a bug in the slave!
|
||||
|
@ -989,7 +995,8 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize
|
|||
if ((tSM == 3) || (tSM == 4))
|
||||
{
|
||||
/* read the assign PDO */
|
||||
Tsize = ecx_readPDOassignCA(context, Slave, ECT_SDO_PDOASSIGN + iSM );
|
||||
Tsize = ecx_readPDOassignCA(context, Slave, Thread_n,
|
||||
ECT_SDO_PDOASSIGN + iSM );
|
||||
/* if a mapping is found */
|
||||
if (Tsize)
|
||||
{
|
||||
|
@ -1445,12 +1452,13 @@ int ec_readPDOassign(uint16 Slave, uint16 PDOassign)
|
|||
/** Read PDO assign structure in Complete Access mode
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] PDOassign = PDO assign object
|
||||
* @param[in] Thread_n = Calling thread index
|
||||
* @return total bitlength of PDO assign
|
||||
* @see ecx_readPDOmap
|
||||
*/
|
||||
int ec_readPDOassignCA(uint16 Slave, uint16 PDOassign)
|
||||
int ec_readPDOassignCA(uint16 Slave, uint16 PDOassign, int Thread_n)
|
||||
{
|
||||
return ecx_readPDOassignCA(&ecx_context, Slave, PDOassign);
|
||||
return ecx_readPDOassignCA(&ecx_context, Slave, Thread_n, PDOassign);
|
||||
}
|
||||
|
||||
/** CoE read PDO mapping.
|
||||
|
@ -1478,14 +1486,15 @@ int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize)
|
|||
* of designated slave. Slave has to support CA, otherwise use ec_readPDOmap().
|
||||
*
|
||||
* @param[in] Slave = Slave number
|
||||
* @param[in] Thread_n = Calling thread index
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
* @see ecx_readPDOmap ec_readPDOmapCA
|
||||
*/
|
||||
int ec_readPDOmapCA(uint16 Slave, int *Osize, int *Isize)
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, int *Osize, int *Isize)
|
||||
{
|
||||
return ecx_readPDOmapCA(&ecx_context, Slave, Osize, Isize);
|
||||
return ecx_readPDOmapCA(&ecx_context, Slave, Thread_n, Osize, Isize);
|
||||
}
|
||||
|
||||
/** CoE read Object Description List.
|
||||
|
|
|
@ -103,7 +103,7 @@ int ec_SDOwrite(uint16 Slave, uint16 Index, uint8 SubIndex,
|
|||
int ec_RxPDO(uint16 Slave, uint16 RxPDOnumber , int psize, void *p);
|
||||
int ec_TxPDO(uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout);
|
||||
int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize);
|
||||
int ec_readPDOmapCA(uint16 Slave, int *Osize, int *Isize);
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, int *Osize, int *Isize);
|
||||
int ec_readODlist(uint16 Slave, ec_ODlistt *pODlist);
|
||||
int ec_readODdescription(uint16 Item, ec_ODlistt *pODlist);
|
||||
int ec_readOEsingle(uint16 Item, uint8 SubI, ec_ODlistt *pODlist, ec_OElistt *pOElist);
|
||||
|
@ -118,7 +118,7 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
int ecx_RxPDO(ecx_contextt *context, uint16 Slave, uint16 RxPDOnumber , int psize, void *p);
|
||||
int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout);
|
||||
int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize);
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize);
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, int *Osize, int *Isize);
|
||||
int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist);
|
||||
int ecx_readODdescription(ecx_contextt *context, uint16 Item, ec_ODlistt *pODlist);
|
||||
int ecx_readOEsingle(ecx_contextt *context, uint16 Item, uint8 SubI, ec_ODlistt *pODlist, ec_OElistt *pOElist);
|
||||
|
|
|
@ -67,18 +67,16 @@
|
|||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
/* define maximum number of concurrent threads in mapping */
|
||||
#define MAX_MAPT 8
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int thread_n;
|
||||
int running;
|
||||
ecx_contextt *context;
|
||||
uint16 slave;
|
||||
} ecx_mapt_t;
|
||||
|
||||
ecx_mapt_t ecx_mapt[MAX_MAPT];
|
||||
OSAL_THREAD_HANDLE ecx_threadh[MAX_MAPT];
|
||||
ecx_mapt_t ecx_mapt[EC_MAX_MAPT];
|
||||
OSAL_THREAD_HANDLE ecx_threadh[EC_MAX_MAPT];
|
||||
|
||||
#ifdef EC_VER1
|
||||
/** Slave configuration structure */
|
||||
|
@ -665,7 +663,7 @@ static int ecx_lookup_mapping(ecx_contextt *context, uint16 slave, int *Osize, i
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave)
|
||||
static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
|
||||
{
|
||||
int Isize, Osize;
|
||||
int rval;
|
||||
|
@ -691,7 +689,7 @@ static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave)
|
|||
if (context->slavelist[slave].CoEdetails & ECT_COEDET_SDOCA) /* has Complete Access */
|
||||
{
|
||||
/* read PDO mapping via CoE and use Complete Access */
|
||||
rval = ecx_readPDOmapCA(context, slave, &Osize, &Isize);
|
||||
rval = ecx_readPDOmapCA(context, slave, thread_n, &Osize, &Isize);
|
||||
}
|
||||
if (!rval) /* CA not available or not succeeded */
|
||||
{
|
||||
|
@ -823,7 +821,7 @@ OSAL_THREAD_FUNC ecx_mapper_thread(void *param)
|
|||
{
|
||||
ecx_mapt_t *maptp;
|
||||
maptp = param;
|
||||
ecx_map_coe_soe(maptp->context, maptp->slave);
|
||||
ecx_map_coe_soe(maptp->context, maptp->slave, maptp->thread_n);
|
||||
maptp->running = 0;
|
||||
}
|
||||
|
||||
|
@ -831,11 +829,11 @@ static int ecx_find_mapt(void)
|
|||
{
|
||||
int p;
|
||||
p = 0;
|
||||
while((p < MAX_MAPT) && ecx_mapt[p].running)
|
||||
while((p < EC_MAX_MAPT) && ecx_mapt[p].running)
|
||||
{
|
||||
p++;
|
||||
}
|
||||
if(p < MAX_MAPT)
|
||||
if(p < EC_MAX_MAPT)
|
||||
{
|
||||
return p;
|
||||
}
|
||||
|
@ -849,7 +847,7 @@ static int ecx_get_threadcount(void)
|
|||
{
|
||||
int thrc, thrn;
|
||||
thrc = 0;
|
||||
for(thrn = 0 ; thrn < MAX_MAPT ; thrn++)
|
||||
for(thrn = 0 ; thrn < EC_MAX_MAPT ; thrn++)
|
||||
{
|
||||
thrc += ecx_mapt[thrn].running;
|
||||
}
|
||||
|
@ -887,7 +885,7 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
context->grouplist[group].outputsWKC = 0;
|
||||
context->grouplist[group].inputsWKC = 0;
|
||||
|
||||
for(thrn = 0 ; thrn < MAX_MAPT ; thrn++)
|
||||
for(thrn = 0 ; thrn < EC_MAX_MAPT ; thrn++)
|
||||
{
|
||||
ecx_mapt[thrn].running = 0;
|
||||
}
|
||||
|
@ -896,10 +894,10 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
{
|
||||
if (!group || (group == context->slavelist[slave].group))
|
||||
{
|
||||
if(MAX_MAPT <= 1)
|
||||
if(EC_MAX_MAPT <= 1)
|
||||
{
|
||||
/* serialised version */
|
||||
ecx_map_coe_soe(context, slave);
|
||||
ecx_map_coe_soe(context, slave, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -910,6 +908,7 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
}
|
||||
ecx_mapt[thrn].context = context;
|
||||
ecx_mapt[thrn].slave = slave;
|
||||
ecx_mapt[thrn].thread_n = thrn;
|
||||
ecx_mapt[thrn].running = 1;
|
||||
osal_thread_create(&(ecx_threadh[thrn]), 128000,
|
||||
&ecx_mapper_thread, &(ecx_mapt[thrn]));
|
||||
|
|
|
@ -117,11 +117,11 @@ static ec_eringt ec_elist;
|
|||
static ec_idxstackT ec_idxstack;
|
||||
|
||||
/** SyncManager Communication Type struct to store data of one slave */
|
||||
static ec_SMcommtypet ec_SMcommtype;
|
||||
static ec_SMcommtypet ec_SMcommtype[EC_MAX_MAPT];
|
||||
/** PDO assign struct to store data of one slave */
|
||||
static ec_PDOassignt ec_PDOassign;
|
||||
static ec_PDOassignt ec_PDOassign[EC_MAX_MAPT];
|
||||
/** PDO description struct to store data of one slave */
|
||||
static ec_PDOdesct ec_PDOdesc;
|
||||
static ec_PDOdesct ec_PDOdesc[EC_MAX_MAPT];
|
||||
|
||||
/** buffer for EEPROM SM data */
|
||||
static ec_eepromSMt ec_SM;
|
||||
|
@ -136,27 +136,27 @@ ecx_portt ecx_port;
|
|||
ecx_redportt ecx_redport;
|
||||
|
||||
ecx_contextt ecx_context = {
|
||||
&ecx_port, // .port =
|
||||
&ec_slave[0], // .slavelist =
|
||||
&ec_slavecount, // .slavecount =
|
||||
EC_MAXSLAVE, // .maxslave =
|
||||
&ec_group[0], // .grouplist =
|
||||
EC_MAXGROUP, // .maxgroup =
|
||||
&ec_esibuf[0], // .esibuf =
|
||||
&ec_esimap[0], // .esimap =
|
||||
0, // .esislave =
|
||||
&ec_elist, // .elist =
|
||||
&ec_idxstack, // .idxstack =
|
||||
&EcatError, // .ecaterror =
|
||||
0, // .DCtO =
|
||||
0, // .DCl =
|
||||
&ec_DCtime, // .DCtime =
|
||||
&ec_SMcommtype, // .SMcommtype =
|
||||
&ec_PDOassign, // .PDOassign =
|
||||
&ec_PDOdesc, // .PDOdesc =
|
||||
&ec_SM, // .eepSM =
|
||||
&ec_FMMU, // .eepFMMU =
|
||||
NULL // .FOEhook()
|
||||
&ecx_port, // .port =
|
||||
&ec_slave[0], // .slavelist =
|
||||
&ec_slavecount, // .slavecount =
|
||||
EC_MAXSLAVE, // .maxslave =
|
||||
&ec_group[0], // .grouplist =
|
||||
EC_MAXGROUP, // .maxgroup =
|
||||
&ec_esibuf[0], // .esibuf =
|
||||
&ec_esimap[0], // .esimap =
|
||||
0, // .esislave =
|
||||
&ec_elist, // .elist =
|
||||
&ec_idxstack, // .idxstack =
|
||||
&EcatError, // .ecaterror =
|
||||
0, // .DCtO =
|
||||
0, // .DCl =
|
||||
&ec_DCtime, // .DCtime =
|
||||
&ec_SMcommtype[0], // .SMcommtype =
|
||||
&ec_PDOassign[0], // .PDOassign =
|
||||
&ec_PDOdesc[0], // .PDOdesc =
|
||||
&ec_SM, // .eepSM =
|
||||
&ec_FMMU, // .eepFMMU =
|
||||
NULL // .FOEhook()
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -73,6 +73,8 @@ extern "C"
|
|||
#define EC_MAXFMMU 4
|
||||
/** max. Adapter */
|
||||
#define EC_MAXLEN_ADAPTERNAME 128
|
||||
/** define maximum number of concurrent threads in mapping */
|
||||
#define EC_MAX_MAPT 8
|
||||
|
||||
typedef struct ec_adapter ec_adaptert;
|
||||
struct ec_adapter
|
||||
|
|
Loading…
Reference in New Issue