Copter: make sure motors go through GROUND_IDLE at startup even when in air mode

This commit is contained in:
Andy Piper 2022-09-03 15:21:46 +01:00 committed by Peter Hall
parent 2cc9f1463e
commit fce1fa6752
2 changed files with 12 additions and 4 deletions

View File

@ -7,7 +7,6 @@
/*
* Init and run calls for acro flight mode
*/
void ModeAcro::run()
{
// convert the input to the desired body frame rate
@ -17,8 +16,13 @@ void ModeAcro::run()
if (!motors->armed()) {
// Motors should be Stopped
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
} else if (copter.ap.throttle_zero && copter.air_mode != AirMode::AIRMODE_ENABLED) {
// Attempting to Land, if airmode is enabled only an actual landing will spool down the motors
} else if (copter.ap.throttle_zero
|| (copter.air_mode == AirMode::AIRMODE_ENABLED && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN)) {
// throttle_zero is never true in air mode, but the motors should be allowed to go through ground idle
// in order to facilitate the spoolup block
// Attempting to Land or motors not yet spinning
// if airmode is enabled only an actual landing will spool down the motors
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);

View File

@ -21,7 +21,11 @@ void ModeStabilize::run()
if (!motors->armed()) {
// Motors should be Stopped
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 && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN)) {
// throttle_zero is never true in air mode, but the motors should be allowed to go through ground idle
// in order to facilitate the spoolup block
// Attempting to Land
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
} else {