Browse Source

Copter: Allow safe shutdown before disarming

master
bnsgeyer 6 years ago committed by Randy Mackay
parent
commit
f96da56ad6
  1. 2
      ArduCopter/mode_auto.cpp
  2. 4
      ArduCopter/mode_land.cpp
  3. 2
      ArduCopter/mode_rtl.cpp

2
ArduCopter/mode_auto.cpp

@ -810,7 +810,7 @@ void Copter::ModeAuto::spline_run() @@ -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();
}

4
ArduCopter/mode_land.cpp

@ -54,7 +54,7 @@ void Copter::ModeLand::run() @@ -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() @@ -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();
}

2
ArduCopter/mode_rtl.cpp

@ -357,7 +357,7 @@ void Copter::ModeRTL::land_run(bool disarm_on_land) @@ -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();
}

Loading…
Cancel
Save