Copter: Allow safe shutdown before disarming

This commit is contained in:
bnsgeyer 2019-03-11 19:25:38 -04:00 committed by Randy Mackay
parent 7ff3a49a10
commit f96da56ad6
3 changed files with 4 additions and 4 deletions

View File

@ -810,7 +810,7 @@ void Copter::ModeAuto::spline_run()
void Copter::ModeAuto::land_run() void Copter::ModeAuto::land_run()
{ {
// disarm when the landing detector says we've landed // disarm when the landing detector says we've landed
if (ap.land_complete) { if (ap.land_complete && motors->get_spool_mode() == AP_Motors::GROUND_IDLE) {
copter.init_disarm_motors(); copter.init_disarm_motors();
} }

View File

@ -54,7 +54,7 @@ void Copter::ModeLand::run()
void Copter::ModeLand::gps_run() void Copter::ModeLand::gps_run()
{ {
// disarm when the landing detector says we've landed // disarm when the landing detector says we've landed
if (ap.land_complete) { if (ap.land_complete && motors->get_spool_mode() == AP_Motors::GROUND_IDLE) {
copter.init_disarm_motors(); copter.init_disarm_motors();
} }
@ -105,7 +105,7 @@ void Copter::ModeLand::nogps_run()
} }
// disarm when the landing detector says we've landed // disarm when the landing detector says we've landed
if (ap.land_complete) { if (ap.land_complete && motors->get_spool_mode() == AP_Motors::GROUND_IDLE) {
copter.init_disarm_motors(); copter.init_disarm_motors();
} }

View File

@ -357,7 +357,7 @@ void Copter::ModeRTL::land_run(bool disarm_on_land)
_state_complete = ap.land_complete; _state_complete = ap.land_complete;
// disarm when the landing detector says we've landed // disarm when the landing detector says we've landed
if (disarm_on_land && ap.land_complete) { if (disarm_on_land && ap.land_complete && motors->get_spool_mode() == AP_Motors::GROUND_IDLE) {
copter.init_disarm_motors(); copter.init_disarm_motors();
} }