AP_Vehicle: check for motors being nullptr

this can happen with plane with Q_ENABLE=0
This commit is contained in:
Andrew Tridgell 2022-10-06 11:17:07 +11:00 committed by Randy Mackay
parent 6a0bd4c88e
commit e072655649
1 changed files with 1 additions and 1 deletions

View File

@ -481,7 +481,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch)
} }
const AP_Motors* motors = AP::motors(); const AP_Motors* motors = AP::motors();
if (motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) { if (motors != nullptr && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) {
notch.set_inactive(true); notch.set_inactive(true);
} else { } else {
notch.set_inactive(false); notch.set_inactive(false);