AP_HAL_SITL: check that _sitl is not nullptr before using it

This commit is contained in:
Pierre Kancir 2021-08-13 10:07:37 +02:00 committed by Peter Barker
parent c91c570814
commit aebe2beba5
1 changed files with 1 additions and 1 deletions

View File

@ -162,7 +162,7 @@ void SITL_State::_fdm_input_step(void)
}
// simulate RC input at 50Hz
if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail != SITL::SIM::SITL_RCFail_NoPulses) {
if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl != nullptr && _sitl->rc_fail != SITL::SIM::SITL_RCFail_NoPulses) {
last_pwm_input = AP_HAL::millis();
new_rc_input = true;
}