diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index e379e3ce81..37f5e75ebb 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -810,7 +810,7 @@ void Copter::ModeAuto::spline_run() void Copter::ModeAuto::land_run() { // 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(); } diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 312774ab79..13aa04691c 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -54,7 +54,7 @@ void Copter::ModeLand::run() void Copter::ModeLand::gps_run() { // 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(); } @@ -105,7 +105,7 @@ void Copter::ModeLand::nogps_run() } // 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(); } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index a2d8651468..3487972b9b 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -357,7 +357,7 @@ void Copter::ModeRTL::land_run(bool disarm_on_land) _state_complete = ap.land_complete; // 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(); }