mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: make can broadcast threadsafe, like can_printf call from lua thread
This commit is contained in:
parent
a717283c62
commit
27b202e984
|
@ -583,6 +583,8 @@ public:
|
||||||
#if AP_AHRS_ENABLED
|
#if AP_AHRS_ENABLED
|
||||||
AP_AHRS ahrs;
|
AP_AHRS ahrs;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
HAL_Semaphore canard_broadcast_semaphore;
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifndef CAN_APP_NODE_NAME
|
#ifndef CAN_APP_NODE_NAME
|
||||||
|
|
|
@ -1055,6 +1055,7 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature,
|
||||||
uint16_t payload_len,
|
uint16_t payload_len,
|
||||||
uint8_t iface_mask)
|
uint8_t iface_mask)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(canard_broadcast_semaphore);
|
||||||
const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID;
|
const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID;
|
||||||
if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
|
if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -1939,12 +1940,15 @@ void AP_Periph_FW::can_update()
|
||||||
// allow for user enabling/disabling CANFD at runtime
|
// allow for user enabling/disabling CANFD at runtime
|
||||||
dronecan.canard.tao_disabled = g.can_fdmode == 1;
|
dronecan.canard.tao_disabled = g.can_fdmode == 1;
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
processTx();
|
WITH_SEMAPHORE(canard_broadcast_semaphore);
|
||||||
processRx();
|
processTx();
|
||||||
|
processRx();
|
||||||
#if HAL_PERIPH_CAN_MIRROR
|
#if HAL_PERIPH_CAN_MIRROR
|
||||||
processMirror();
|
processMirror();
|
||||||
#endif // HAL_PERIPH_CAN_MIRROR
|
#endif // HAL_PERIPH_CAN_MIRROR
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue