AP_Periph: fixed thread safety of push_force

This commit is contained in:
Andrew Tridgell 2020-01-10 18:13:34 +11:00
parent 3556f33051
commit 924e012fa7

View File

@ -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);