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 Peter Barker
parent 8fb00f02f4
commit 1796cd5394

View File

@ -485,7 +485,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch &notch)
}
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);
} else {
notch.set_inactive(false);