From e0726556491751207446fe20b29a91990a69af59 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 6 Oct 2022 11:17:07 +1100 Subject: [PATCH] AP_Vehicle: check for motors being nullptr this can happen with plane with Q_ENABLE=0 --- libraries/AP_Vehicle/AP_Vehicle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index cf2c40bbd5..77d183d30f 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -481,7 +481,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch) } 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);