Warnings omitted (#144)
* All Warnings omitted Now all warnings that came up in previous versions are fixed in a clean way directly in the code. Inlcudes: Shadowing Missing default cases Missing cases in switch statements unused variables Pointer problems Function declarations' visibility * Default case for NMTsendCommand Default case was not catched before and could led to errors. * fix typo when omitting warnings * Omitting more warnings, and fix TIME->CANrxNew nulling Inlcudes: large integer implicitly truncated to unsigned type this statement may fall through * rename CO_this to co * fix CO_process_SYNC name (CANopenNode master merging issue) Co-authored-by: Michele B. <MicheleBlank@gmx-topmail.de> ---- Verified before merge. It is cleanup, no deep changes.
This commit is contained in:
parent
3d41f20adb
commit
f2283e3ca9
92
CANopen.c
92
CANopen.c
|
@ -149,12 +149,39 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
/* These declarations here are needed in the case the switches for the project
|
||||
change the visibility in the headers in a way that the compiler doesn't see an declaration anymore */
|
||||
|
||||
#if CO_NO_LSS_SERVER == 0 /* LSS Server means LSS slave */
|
||||
|
||||
CO_ReturnError_t CO_new(void);
|
||||
|
||||
CO_ReturnError_t CO_CANinit(
|
||||
void *CANdriverState,
|
||||
uint16_t bitRate);
|
||||
|
||||
CO_ReturnError_t CO_LSSinit(
|
||||
uint8_t nodeId,
|
||||
uint16_t bitRate);
|
||||
|
||||
CO_ReturnError_t CO_CANopenInit(
|
||||
uint8_t nodeId);
|
||||
|
||||
#else /* CO_NO_LSS_SERVER == 0 */
|
||||
|
||||
CO_ReturnError_t CO_init(
|
||||
void *CANdriverState,
|
||||
uint8_t nodeId,
|
||||
uint16_t bitRate);
|
||||
|
||||
#endif /* CO_NO_LSS_SERVER == 0 */
|
||||
|
||||
|
||||
/* Helper function for NMT master *********************************************/
|
||||
#if CO_NO_NMT_MASTER == 1
|
||||
CO_CANtx_t *NMTM_txBuff = 0;
|
||||
|
||||
CO_ReturnError_t CO_sendNMTcommand(CO_t *CO, uint8_t command, uint8_t nodeID){
|
||||
CO_ReturnError_t CO_sendNMTcommand(CO_t *co, uint8_t command, uint8_t nodeID){
|
||||
if(NMTM_txBuff == 0){
|
||||
/* error, CO_CANtxBufferInit() was not called for this buffer. */
|
||||
return CO_ERROR_TX_UNCONFIGURED; /* -11 */
|
||||
|
@ -162,30 +189,42 @@
|
|||
NMTM_txBuff->data[0] = command;
|
||||
NMTM_txBuff->data[1] = nodeID;
|
||||
|
||||
CO_ReturnError_t error = CO_ERROR_NO;
|
||||
|
||||
/* Apply NMT command also to this node, if set so. */
|
||||
if(nodeID == 0 || nodeID == CO->NMT->nodeId){
|
||||
if(nodeID == 0 || nodeID == co->NMT->nodeId){
|
||||
switch(command){
|
||||
case CO_NMT_ENTER_OPERATIONAL:
|
||||
if((*CO->NMT->emPr->errorRegister) == 0) {
|
||||
CO->NMT->operatingState = CO_NMT_OPERATIONAL;
|
||||
if((*co->NMT->emPr->errorRegister) == 0) {
|
||||
co->NMT->operatingState = CO_NMT_OPERATIONAL;
|
||||
}
|
||||
break;
|
||||
case CO_NMT_ENTER_STOPPED:
|
||||
CO->NMT->operatingState = CO_NMT_STOPPED;
|
||||
co->NMT->operatingState = CO_NMT_STOPPED;
|
||||
break;
|
||||
case CO_NMT_ENTER_PRE_OPERATIONAL:
|
||||
CO->NMT->operatingState = CO_NMT_PRE_OPERATIONAL;
|
||||
co->NMT->operatingState = CO_NMT_PRE_OPERATIONAL;
|
||||
break;
|
||||
case CO_NMT_RESET_NODE:
|
||||
CO->NMT->resetCommand = CO_RESET_APP;
|
||||
co->NMT->resetCommand = CO_RESET_APP;
|
||||
break;
|
||||
case CO_NMT_RESET_COMMUNICATION:
|
||||
CO->NMT->resetCommand = CO_RESET_COMM;
|
||||
co->NMT->resetCommand = CO_RESET_COMM;
|
||||
break;
|
||||
default:
|
||||
error = CO_ERROR_ILLEGAL_ARGUMENT;
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
return CO_CANsend(CO->CANmodule[0], NMTM_txBuff); /* 0 = success */
|
||||
if(error == CO_ERROR_NO)
|
||||
return CO_CANsend(co->CANmodule[0], NMTM_txBuff); /* 0 = success */
|
||||
else
|
||||
{
|
||||
return error;
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -775,7 +814,7 @@ void CO_delete(void *CANdriverState){
|
|||
|
||||
/******************************************************************************/
|
||||
CO_NMT_reset_cmd_t CO_process(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
uint16_t timeDifference_ms,
|
||||
uint16_t *timerNext_ms)
|
||||
{
|
||||
|
@ -786,14 +825,14 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
static uint16_t ms50 = 0;
|
||||
#endif /* CO_USE_LEDS */
|
||||
|
||||
if(CO->NMT->operatingState == CO_NMT_PRE_OPERATIONAL || CO->NMT->operatingState == CO_NMT_OPERATIONAL)
|
||||
if(co->NMT->operatingState == CO_NMT_PRE_OPERATIONAL || co->NMT->operatingState == CO_NMT_OPERATIONAL)
|
||||
NMTisPreOrOperational = true;
|
||||
|
||||
#ifdef CO_USE_LEDS
|
||||
ms50 += timeDifference_ms;
|
||||
if(ms50 >= 50){
|
||||
ms50 -= 50;
|
||||
CO_NMT_blinkingProcess50ms(CO->NMT);
|
||||
CO_NMT_blinkingProcess50ms(co->NMT);
|
||||
}
|
||||
#endif /* CO_USE_LEDS */
|
||||
if(timerNext_ms != NULL){
|
||||
|
@ -805,7 +844,7 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
|
||||
for(i=0; i<CO_NO_SDO_SERVER; i++){
|
||||
CO_SDO_process(
|
||||
CO->SDO[i],
|
||||
co->SDO[i],
|
||||
NMTisPreOrOperational,
|
||||
timeDifference_ms,
|
||||
1000,
|
||||
|
@ -813,7 +852,7 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
}
|
||||
|
||||
CO_EM_process(
|
||||
CO->emPr,
|
||||
co->emPr,
|
||||
NMTisPreOrOperational,
|
||||
timeDifference_ms * 10,
|
||||
OD_inhibitTimeEMCY,
|
||||
|
@ -821,7 +860,7 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
|
||||
|
||||
reset = CO_NMT_process(
|
||||
CO->NMT,
|
||||
co->NMT,
|
||||
timeDifference_ms,
|
||||
OD_producerHeartbeatTime,
|
||||
OD_NMTStartup,
|
||||
|
@ -831,13 +870,13 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
|
||||
|
||||
CO_HBconsumer_process(
|
||||
CO->HBcons,
|
||||
co->HBcons,
|
||||
NMTisPreOrOperational,
|
||||
timeDifference_ms);
|
||||
|
||||
#if CO_NO_TIME == 1
|
||||
CO_TIME_process(
|
||||
CO->TIME,
|
||||
co->TIME,
|
||||
timeDifference_ms);
|
||||
#endif
|
||||
|
||||
|
@ -848,17 +887,17 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
/******************************************************************************/
|
||||
#if CO_NO_SYNC == 1
|
||||
bool_t CO_process_SYNC(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
uint32_t timeDifference_us)
|
||||
{
|
||||
bool_t syncWas = false;
|
||||
|
||||
switch(CO_SYNC_process(CO->SYNC, timeDifference_us, OD_synchronousWindowLength)){
|
||||
switch(CO_SYNC_process(co->SYNC, timeDifference_us, OD_synchronousWindowLength)){
|
||||
case 1: //immediately after the SYNC message
|
||||
syncWas = true;
|
||||
break;
|
||||
case 2: //outside SYNC window
|
||||
CO_CANclearPendingSyncPDOs(CO->CANmodule[0]);
|
||||
CO_CANclearPendingSyncPDOs(co->CANmodule[0]);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -868,20 +907,20 @@ bool_t CO_process_SYNC(
|
|||
|
||||
/******************************************************************************/
|
||||
void CO_process_RPDO(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
bool_t syncWas)
|
||||
{
|
||||
int16_t i;
|
||||
|
||||
for(i=0; i<CO_NO_RPDO; i++){
|
||||
CO_RPDO_process(CO->RPDO[i], syncWas);
|
||||
CO_RPDO_process(co->RPDO[i], syncWas);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/******************************************************************************/
|
||||
void CO_process_TPDO(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
bool_t syncWas,
|
||||
uint32_t timeDifference_us)
|
||||
{
|
||||
|
@ -889,9 +928,8 @@ void CO_process_TPDO(
|
|||
|
||||
/* Verify PDO Change Of State and process PDOs */
|
||||
for(i=0; i<CO_NO_TPDO; i++){
|
||||
if(!CO->TPDO[i]->sendRequest)
|
||||
CO->TPDO[i]->sendRequest = CO_TPDOisCOS(CO->TPDO[i]);
|
||||
|
||||
CO_TPDO_process(CO->TPDO[i], syncWas, timeDifference_us);
|
||||
if(!co->TPDO[i]->sendRequest)
|
||||
co->TPDO[i]->sendRequest = CO_TPDOisCOS(co->TPDO[i]);
|
||||
CO_TPDO_process(co->TPDO[i], syncWas, timeDifference_us);
|
||||
}
|
||||
}
|
||||
|
|
20
CANopen.h
20
CANopen.h
|
@ -154,7 +154,7 @@ typedef struct{
|
|||
* object. Follow the code in CANopen.c file. If macro CO_NO_NMT_MASTER is 1,
|
||||
* function CO_sendNMTcommand can be used to send NMT master message.
|
||||
*
|
||||
* @param CO CANopen object.
|
||||
* @param co CANopen object.
|
||||
* @param command NMT command.
|
||||
* @param nodeID Node ID.
|
||||
*
|
||||
|
@ -162,7 +162,7 @@ typedef struct{
|
|||
* @return other: same as CO_CANsend().
|
||||
*/
|
||||
#if CO_NO_NMT_MASTER == 1
|
||||
CO_ReturnError_t CO_sendNMTcommand(CO_t *CO, uint8_t command, uint8_t nodeID);
|
||||
CO_ReturnError_t CO_sendNMTcommand(CO_t *co, uint8_t command, uint8_t nodeID);
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -254,7 +254,7 @@ void CO_delete(void *CANdriverState);
|
|||
* Function must be called cyclically. It processes all "asynchronous" CANopen
|
||||
* objects.
|
||||
*
|
||||
* @param CO This object
|
||||
* @param co CANopen object.
|
||||
* @param timeDifference_ms Time difference from previous function call in [milliseconds].
|
||||
* @param timerNext_ms Return value - info to OS - maximum delay after function
|
||||
* should be called next time in [milliseconds]. Value can be used for OS
|
||||
|
@ -266,7 +266,7 @@ void CO_delete(void *CANdriverState);
|
|||
* @return #CO_NMT_reset_cmd_t from CO_NMT_process().
|
||||
*/
|
||||
CO_NMT_reset_cmd_t CO_process(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
uint16_t timeDifference_ms,
|
||||
uint16_t *timerNext_ms);
|
||||
|
||||
|
@ -278,13 +278,13 @@ CO_NMT_reset_cmd_t CO_process(
|
|||
* Function must be called cyclically from real time thread with constant
|
||||
* interval (1ms typically). It processes SYNC CANopen objects.
|
||||
*
|
||||
* @param CO This object.
|
||||
* @param co CANopen object.
|
||||
* @param timeDifference_us Time difference from previous function call in [microseconds].
|
||||
*
|
||||
* @return True, if CANopen SYNC message was just received or transmitted.
|
||||
*/
|
||||
bool_t CO_process_SYNC(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
uint32_t timeDifference_us);
|
||||
#endif
|
||||
|
||||
|
@ -294,11 +294,11 @@ bool_t CO_process_SYNC(
|
|||
* Function must be called cyclically from real time thread with constant.
|
||||
* interval (1ms typically). It processes receive PDO CANopen objects.
|
||||
*
|
||||
* @param CO This object.
|
||||
* @param co CANopen object.
|
||||
* @param syncWas True, if CANopen SYNC message was just received or transmitted.
|
||||
*/
|
||||
void CO_process_RPDO(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
bool_t syncWas);
|
||||
|
||||
/**
|
||||
|
@ -307,12 +307,12 @@ void CO_process_RPDO(
|
|||
* Function must be called cyclically from real time thread with constant.
|
||||
* interval (1ms typically). It processes transmit PDO CANopen objects.
|
||||
*
|
||||
* @param CO This object.
|
||||
* @param co CANopen object.
|
||||
* @param syncWas True, if CANopen SYNC message was just received or transmitted.
|
||||
* @param timeDifference_us Time difference from previous function call in [microseconds].
|
||||
*/
|
||||
void CO_process_TPDO(
|
||||
CO_t *CO,
|
||||
CO_t *co,
|
||||
bool_t syncWas,
|
||||
uint32_t timeDifference_us);
|
||||
|
||||
|
|
|
@ -309,12 +309,12 @@ void CO_EM_process(
|
|||
|
||||
/* write to 'pre-defined error field' (object dictionary, index 0x1003) */
|
||||
if(emPr->preDefErr){
|
||||
uint8_t i;
|
||||
uint8_t j;
|
||||
|
||||
if(emPr->preDefErrNoOfErrors < emPr->preDefErrSize)
|
||||
emPr->preDefErrNoOfErrors++;
|
||||
for(i=emPr->preDefErrNoOfErrors-1; i>0; i--)
|
||||
emPr->preDefErr[i] = emPr->preDefErr[i-1];
|
||||
for(j=emPr->preDefErrNoOfErrors-1; j>0; j--)
|
||||
emPr->preDefErr[j] = emPr->preDefErr[j-1];
|
||||
emPr->preDefErr[0] = preDEF;
|
||||
}
|
||||
|
||||
|
|
|
@ -804,6 +804,7 @@ static CO_LSSmaster_return_t CO_LSSmaster_FsScanInitiate(
|
|||
case CO_LSSmaster_FS_MATCH:
|
||||
/* No scanning requested */
|
||||
return CO_LSSmaster_SCAN_FINISHED;
|
||||
case CO_LSSmaster_FS_SKIP:
|
||||
default:
|
||||
return CO_LSSmaster_SCAN_FAILED;
|
||||
}
|
||||
|
@ -833,6 +834,7 @@ static CO_LSSmaster_return_t CO_LSSmaster_FsScanWait(
|
|||
case CO_LSSmaster_FS_MATCH:
|
||||
/* No scanning requested */
|
||||
return CO_LSSmaster_SCAN_FINISHED;
|
||||
case CO_LSSmaster_FS_SKIP:
|
||||
default:
|
||||
return CO_LSSmaster_SCAN_FAILED;
|
||||
}
|
||||
|
@ -890,6 +892,7 @@ static CO_LSSmaster_return_t CO_LSSmaster_FsVerifyInitiate(
|
|||
/* ID given by user */
|
||||
LSSmaster->fsIdNumber = idNumberCheck;
|
||||
break;
|
||||
case CO_LSSmaster_FS_SKIP:
|
||||
default:
|
||||
return CO_LSSmaster_SCAN_FAILED;
|
||||
}
|
||||
|
@ -1089,6 +1092,8 @@ CO_LSSmaster_return_t CO_LSSmaster_IdentifyFastscan(
|
|||
}
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (ret != CO_LSSmaster_WAIT_SLAVE) {
|
||||
|
|
|
@ -66,6 +66,8 @@ static void CO_NMT_receive(void *object, const CO_CANrxMsg_t *msg){
|
|||
case CO_NMT_RESET_COMMUNICATION:
|
||||
NMT->resetCommand = CO_RESET_COMM;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if(NMT->pFunctNMT!=NULL && currentOperatingState!=NMT->operatingState){
|
||||
|
@ -168,6 +170,7 @@ void CO_NMT_blinkingProcess50ms(CO_NMT_t *NMT){
|
|||
case 4: NMT->LEDdoubleFlash = -104; break;
|
||||
case -100: NMT->LEDdoubleFlash = 100; break;
|
||||
case 104: NMT->LEDdoubleFlash = -20; break;
|
||||
default: break;
|
||||
}
|
||||
|
||||
switch(++NMT->LEDtripleFlash){
|
||||
|
@ -176,6 +179,7 @@ void CO_NMT_blinkingProcess50ms(CO_NMT_t *NMT){
|
|||
case 104: NMT->LEDtripleFlash = -114; break;
|
||||
case -110: NMT->LEDtripleFlash = 110; break;
|
||||
case 114: NMT->LEDtripleFlash = -20; break;
|
||||
default: break;
|
||||
}
|
||||
|
||||
switch(++NMT->LEDquadrupleFlash){
|
||||
|
@ -186,6 +190,7 @@ void CO_NMT_blinkingProcess50ms(CO_NMT_t *NMT){
|
|||
case 114: NMT->LEDquadrupleFlash = -124; break;
|
||||
case -120: NMT->LEDquadrupleFlash = 120; break;
|
||||
case 124: NMT->LEDquadrupleFlash = -20; break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
#endif /* CO_USE_LEDS */
|
||||
|
@ -252,6 +257,7 @@ CO_NMT_reset_cmd_t CO_NMT_process(
|
|||
case CO_NMT_STOPPED: NMT->LEDgreenRun = NMT->LEDsingleFlash; break;
|
||||
case CO_NMT_PRE_OPERATIONAL: NMT->LEDgreenRun = NMT->LEDblinking; break;
|
||||
case CO_NMT_OPERATIONAL: NMT->LEDgreenRun = 1; break;
|
||||
default: break;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -422,14 +422,16 @@ static CO_SDO_abortCode_t CO_ODF_RPDOcom(CO_ODF_arg_t *ODF_arg){
|
|||
/* Reading Object Dictionary variable */
|
||||
if(ODF_arg->reading){
|
||||
if(ODF_arg->subIndex == 1){
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
|
||||
/* if default COB ID is used, write default value here */
|
||||
if(((*value)&0xFFFF) == RPDO->defaultCOB_ID && RPDO->defaultCOB_ID)
|
||||
*value += RPDO->nodeId;
|
||||
if(((value)&0xFFFF) == RPDO->defaultCOB_ID && RPDO->defaultCOB_ID)
|
||||
value += RPDO->nodeId;
|
||||
|
||||
/* If PDO is not valid, set bit 31 */
|
||||
if(!RPDO->valid) *value |= 0x80000000L;
|
||||
if(!RPDO->valid) value |= 0x80000000L;
|
||||
|
||||
CO_setUint32(ODF_arg->data, value);
|
||||
}
|
||||
return CO_SDO_AB_NONE;
|
||||
}
|
||||
|
@ -441,24 +443,25 @@ static CO_SDO_abortCode_t CO_ODF_RPDOcom(CO_ODF_arg_t *ODF_arg){
|
|||
return CO_SDO_AB_DATA_DEV_STATE; /* Data cannot be transferred or stored to the application because of the present device state. */
|
||||
|
||||
if(ODF_arg->subIndex == 1){ /* COB_ID */
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
|
||||
/* bits 11...29 must be zero */
|
||||
if(*value & 0x3FFF8000L)
|
||||
if(value & 0x3FFF8000L)
|
||||
return CO_SDO_AB_INVALID_VALUE; /* Invalid value for parameter (download only). */
|
||||
|
||||
/* if default COB-ID is being written, write defaultCOB_ID without nodeId */
|
||||
if(((*value)&0xFFFF) == (RPDO->defaultCOB_ID + RPDO->nodeId)){
|
||||
*value &= 0xC0000000L;
|
||||
*value += RPDO->defaultCOB_ID;
|
||||
if(((value)&0xFFFF) == (RPDO->defaultCOB_ID + RPDO->nodeId)){
|
||||
value &= 0xC0000000L;
|
||||
value += RPDO->defaultCOB_ID;
|
||||
CO_setUint32(ODF_arg->data, value);
|
||||
}
|
||||
|
||||
/* if PDO is valid, bits 0..29 can not be changed */
|
||||
if(RPDO->valid && ((*value ^ RPDO->RPDOCommPar->COB_IDUsedByRPDO) & 0x3FFFFFFFL))
|
||||
if(RPDO->valid && ((value ^ RPDO->RPDOCommPar->COB_IDUsedByRPDO) & 0x3FFFFFFFL))
|
||||
return CO_SDO_AB_INVALID_VALUE; /* Invalid value for parameter (download only). */
|
||||
|
||||
/* configure RPDO */
|
||||
CO_RPDOconfigCom(RPDO, *value);
|
||||
CO_RPDOconfigCom(RPDO, value);
|
||||
}
|
||||
else if(ODF_arg->subIndex == 2){ /* Transmission_type */
|
||||
uint8_t *value = (uint8_t*) ODF_arg->data;
|
||||
|
@ -495,14 +498,16 @@ static CO_SDO_abortCode_t CO_ODF_TPDOcom(CO_ODF_arg_t *ODF_arg){
|
|||
/* Reading Object Dictionary variable */
|
||||
if(ODF_arg->reading){
|
||||
if(ODF_arg->subIndex == 1){ /* COB_ID */
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
|
||||
/* if default COB ID is used, write default value here */
|
||||
if(((*value)&0xFFFF) == TPDO->defaultCOB_ID && TPDO->defaultCOB_ID)
|
||||
*value += TPDO->nodeId;
|
||||
if(((value)&0xFFFF) == TPDO->defaultCOB_ID && TPDO->defaultCOB_ID)
|
||||
value += TPDO->nodeId;
|
||||
|
||||
/* If PDO is not valid, set bit 31 */
|
||||
if(!TPDO->valid) *value |= 0x80000000L;
|
||||
if(!TPDO->valid) value |= 0x80000000L;
|
||||
|
||||
CO_setUint32(ODF_arg->data, value);
|
||||
}
|
||||
return CO_SDO_AB_NONE;
|
||||
}
|
||||
|
@ -514,24 +519,26 @@ static CO_SDO_abortCode_t CO_ODF_TPDOcom(CO_ODF_arg_t *ODF_arg){
|
|||
return CO_SDO_AB_DATA_DEV_STATE; /* Data cannot be transferred or stored to the application because of the present device state. */
|
||||
|
||||
if(ODF_arg->subIndex == 1){ /* COB_ID */
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
|
||||
/* bits 11...29 must be zero */
|
||||
if(*value & 0x3FFF8000L)
|
||||
if(value & 0x3FFF8000L)
|
||||
return CO_SDO_AB_INVALID_VALUE; /* Invalid value for parameter (download only). */
|
||||
|
||||
/* if default COB-ID is being written, write defaultCOB_ID without nodeId */
|
||||
if(((*value)&0xFFFF) == (TPDO->defaultCOB_ID + TPDO->nodeId)){
|
||||
*value &= 0xC0000000L;
|
||||
*value += TPDO->defaultCOB_ID;
|
||||
if(((value)&0xFFFF) == (TPDO->defaultCOB_ID + TPDO->nodeId)){
|
||||
value &= 0xC0000000L;
|
||||
value += TPDO->defaultCOB_ID;
|
||||
|
||||
CO_setUint32(ODF_arg->data, value);
|
||||
}
|
||||
|
||||
/* if PDO is valid, bits 0..29 can not be changed */
|
||||
if(TPDO->valid && ((*value ^ TPDO->TPDOCommPar->COB_IDUsedByTPDO) & 0x3FFFFFFFL))
|
||||
if(TPDO->valid && ((value ^ TPDO->TPDOCommPar->COB_IDUsedByTPDO) & 0x3FFFFFFFL))
|
||||
return CO_SDO_AB_INVALID_VALUE; /* Invalid value for parameter (download only). */
|
||||
|
||||
/* configure TPDO */
|
||||
CO_TPDOconfigCom(TPDO, *value, TPDO->CANtxBuff->syncFlag);
|
||||
CO_TPDOconfigCom(TPDO, value, TPDO->CANtxBuff->syncFlag);
|
||||
TPDO->syncCounter = 255;
|
||||
}
|
||||
else if(ODF_arg->subIndex == 2){ /* Transmission_type */
|
||||
|
@ -551,9 +558,9 @@ static CO_SDO_abortCode_t CO_ODF_TPDOcom(CO_ODF_arg_t *ODF_arg){
|
|||
TPDO->inhibitTimer = 0;
|
||||
}
|
||||
else if(ODF_arg->subIndex == 5){ /* Event_Timer */
|
||||
uint16_t *value = (uint16_t*) ODF_arg->data;
|
||||
uint16_t value = CO_getUint16(ODF_arg->data);
|
||||
|
||||
TPDO->eventTimer = ((uint32_t) *value) * 1000;
|
||||
TPDO->eventTimer = ((uint32_t) value) * 1000;
|
||||
}
|
||||
else if(ODF_arg->subIndex == 6){ /* SYNC start value */
|
||||
uint8_t *value = (uint8_t*) ODF_arg->data;
|
||||
|
@ -613,7 +620,7 @@ static CO_SDO_abortCode_t CO_ODF_RPDOmap(CO_ODF_arg_t *ODF_arg){
|
|||
|
||||
/* mappedObject */
|
||||
else{
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
uint8_t* pData;
|
||||
uint8_t length = 0;
|
||||
uint8_t dummy = 0;
|
||||
|
@ -625,7 +632,7 @@ static CO_SDO_abortCode_t CO_ODF_RPDOmap(CO_ODF_arg_t *ODF_arg){
|
|||
/* verify if mapping is correct */
|
||||
return CO_PDOfindMap(
|
||||
RPDO->SDO,
|
||||
*value,
|
||||
value,
|
||||
0,
|
||||
&pData,
|
||||
&length,
|
||||
|
@ -679,7 +686,7 @@ static CO_SDO_abortCode_t CO_ODF_TPDOmap(CO_ODF_arg_t *ODF_arg){
|
|||
|
||||
/* mappedObject */
|
||||
else{
|
||||
uint32_t *value = (uint32_t*) ODF_arg->data;
|
||||
uint32_t value = CO_getUint32(ODF_arg->data);
|
||||
uint8_t* pData;
|
||||
uint8_t length = 0;
|
||||
uint8_t dummy = 0;
|
||||
|
@ -691,7 +698,7 @@ static CO_SDO_abortCode_t CO_ODF_TPDOmap(CO_ODF_arg_t *ODF_arg){
|
|||
/* verify if mapping is correct */
|
||||
return CO_PDOfindMap(
|
||||
TPDO->SDO,
|
||||
*value,
|
||||
value,
|
||||
1,
|
||||
&pData,
|
||||
&length,
|
||||
|
@ -824,14 +831,14 @@ uint8_t CO_TPDOisCOS(CO_TPDO_t *TPDO){
|
|||
ppODdataByte = &TPDO->mapPointer[TPDO->dataLength];
|
||||
|
||||
switch(TPDO->dataLength){
|
||||
case 8: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x80)) return 1;
|
||||
case 7: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x40)) return 1;
|
||||
case 6: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x20)) return 1;
|
||||
case 5: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x10)) return 1;
|
||||
case 4: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x08)) return 1;
|
||||
case 3: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x04)) return 1;
|
||||
case 2: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x02)) return 1;
|
||||
case 1: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x01)) return 1;
|
||||
case 8: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x80)) return 1; // fallthrough
|
||||
case 7: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x40)) return 1; // fallthrough
|
||||
case 6: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x20)) return 1; // fallthrough
|
||||
case 5: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x10)) return 1; // fallthrough
|
||||
case 4: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x08)) return 1; // fallthrough
|
||||
case 3: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x04)) return 1; // fallthrough
|
||||
case 2: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x02)) return 1; // fallthrough
|
||||
case 1: if(*(--pPDOdataByte) != **(--ppODdataByte) && (TPDO->sendIfCOSFlags&0x01)) return 1; // fallthrough
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
|
|
@ -1172,8 +1172,8 @@ int8_t CO_SDO_process(
|
|||
|
||||
/* indicate data size, if known */
|
||||
if(SDO->ODF_arg.dataLengthTotal != 0U){
|
||||
uint32_t len = SDO->ODF_arg.dataLengthTotal;
|
||||
CO_memcpySwap4(&SDO->CANtxBuff->data[4], &len);
|
||||
uint32_t dlentot = SDO->ODF_arg.dataLengthTotal;
|
||||
CO_memcpySwap4(&SDO->CANtxBuff->data[4], &dlentot);
|
||||
SDO->CANtxBuff->data[0] = 0x41U;
|
||||
}
|
||||
else{
|
||||
|
@ -1285,8 +1285,8 @@ int8_t CO_SDO_process(
|
|||
|
||||
/* indicate data size, if known */
|
||||
if(SDO->ODF_arg.dataLengthTotal != 0U){
|
||||
uint32_t len = SDO->ODF_arg.dataLengthTotal;
|
||||
CO_memcpySwap4(&SDO->CANtxBuff->data[4], &len);
|
||||
uint32_t dlentot = SDO->ODF_arg.dataLengthTotal;
|
||||
CO_memcpySwap4(&SDO->CANtxBuff->data[4], &dlentot);
|
||||
SDO->CANtxBuff->data[0] = 0xC6U;
|
||||
}
|
||||
else{
|
||||
|
@ -1313,6 +1313,7 @@ int8_t CO_SDO_process(
|
|||
SDO->state = CO_SDO_ST_UPLOAD_BL_SUBBLOCK;
|
||||
/* continue in next case */
|
||||
}
|
||||
// fallthrough
|
||||
|
||||
case CO_SDO_ST_UPLOAD_BL_SUBBLOCK:{
|
||||
/* is block confirmation received */
|
||||
|
@ -1450,6 +1451,12 @@ int8_t CO_SDO_process(
|
|||
SDO->state = CO_SDO_ST_IDLE;
|
||||
break;
|
||||
}
|
||||
|
||||
case CO_SDO_ST_IDLE:
|
||||
{
|
||||
/* Nothing to do it seems */
|
||||
break;
|
||||
}
|
||||
|
||||
default:{
|
||||
CO_SDO_abort(SDO, CO_SDO_AB_DEVICE_INCOMPAT);/* general internal incompatibility in the device */
|
||||
|
|
|
@ -133,7 +133,7 @@ uint8_t CO_TIME_process(
|
|||
if(TIME->CANrxNew){
|
||||
TIME->timer = 0;
|
||||
ret = 1;
|
||||
TIME->CANrxNew = false;
|
||||
CLEAR_CANrxNew(TIME->CANrxNew);
|
||||
}
|
||||
|
||||
/* TIME producer */
|
||||
|
|
|
@ -77,7 +77,7 @@ CO_ReturnError_t CO_CANmodule_init(
|
|||
|
||||
for(i=0U; i<rxSize; i++){
|
||||
rxArray[i].ident = 0U;
|
||||
rxArray[i].mask = 0xFFFFFFFFU;
|
||||
rxArray[i].mask = (uint16_t)0xFFFFFFFFU;
|
||||
rxArray[i].object = NULL;
|
||||
rxArray[i].pFunct = NULL;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue