Copter: airmode should mean airmode. only idle on landing when in airmode

This commit is contained in:
Andy Piper 2021-09-06 16:33:40 +01:00 committed by Randy Mackay
parent e8e59014ad
commit fbd41b6332

View File

@ -17,8 +17,8 @@ void ModeAcro::run()
if (!motors->armed()) { if (!motors->armed()) {
// Motors should be Stopped // Motors should be Stopped
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
} else if (copter.ap.throttle_zero) { } else if (copter.ap.throttle_zero && copter.air_mode != AirMode::AIRMODE_ENABLED) {
// Attempting to Land // Attempting to Land, if airmode is enabled only an actual landing will spool down the motors
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else { } else {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);