mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Periph: fixed thread safety of push_force
This commit is contained in:
parent
3556f33051
commit
924e012fa7
@ -813,7 +813,14 @@ static void can_rxfull_cb(CANDriver *canp, uint32_t flags)
|
||||
static void processRx(void)
|
||||
{
|
||||
CANRxFrame rxmsg;
|
||||
while (rxbuffer.pop(rxmsg)) {
|
||||
while (true) {
|
||||
bool have_msg;
|
||||
chSysLock();
|
||||
have_msg = rxbuffer.pop(rxmsg);
|
||||
chSysUnlock();
|
||||
if (!have_msg) {
|
||||
break;
|
||||
}
|
||||
CanardCANFrame rx_frame {};
|
||||
|
||||
//palToggleLine(HAL_GPIO_PIN_LED);
|
||||
|
Loading…
Reference in New Issue
Block a user