mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
HAL_SITL: make cork/push safe to call nested
This commit is contained in:
parent
351304ebcb
commit
f257a869ac
@ -69,14 +69,18 @@ void RCOutput::read(uint16_t* period_us, uint8_t len)
|
||||
|
||||
void RCOutput::cork(void)
|
||||
{
|
||||
if (!_corked) {
|
||||
memcpy(_pending, _sitlState->pwm_output, SITL_NUM_CHANNELS * sizeof(uint16_t));
|
||||
_corked = true;
|
||||
}
|
||||
}
|
||||
|
||||
void RCOutput::push(void)
|
||||
{
|
||||
if (_corked) {
|
||||
memcpy(_sitlState->pwm_output, _pending, SITL_NUM_CHANNELS * sizeof(uint16_t));
|
||||
_corked = false;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user