mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_HAL_ChibiOS: check command queue is empty before arming
This commit is contained in:
parent
66fadf53a1
commit
384ecd4a5b
@ -485,7 +485,11 @@ bool RCOutput::prepare_for_arming()
|
|||||||
// force all the ESCs to be active, in the future consider returning false
|
// force all the ESCs to be active, in the future consider returning false
|
||||||
// if ESCs are not active that we require
|
// if ESCs are not active that we require
|
||||||
_active_escs_mask = (en_mask << chan_offset);
|
_active_escs_mask = (en_mask << chan_offset);
|
||||||
|
#ifdef DISABLE_DSHOT
|
||||||
return true;
|
return true;
|
||||||
|
#else
|
||||||
|
return _dshot_command_queue.is_empty();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
||||||
|
Loading…
Reference in New Issue
Block a user