Browse Source

AP_Periph: fixed thread safety of push_force

zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
924e012fa7
  1. 9
      Tools/AP_Periph/can.cpp

9
Tools/AP_Periph/can.cpp

@ -813,7 +813,14 @@ static void can_rxfull_cb(CANDriver *canp, uint32_t flags) @@ -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…
Cancel
Save