mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: check for motors being nullptr
this can happen with plane with Q_ENABLE=0
This commit is contained in:
parent
6a0bd4c88e
commit
e072655649
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue