From fed50aa5c54787be28c6860607252d2511be5271 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 24 Aug 2015 00:58:48 -0700 Subject: [PATCH] Plane: is_crashed flag gets reset too easily This behavior is excessively paranoid about clearing the flag so now it's extra sticky. You can only clear the is_crashed flag when: - changing modes - starting to execute a takeoff wp (if mission/index gets reset while still in auto) - while in takeoff and throttle is suppressed it's held false behavior that was removed: - clear flag when starting to execute any nav cmd (reached next wp) - if while crashed, you "start flying again" (non-sticky) --- ArduPlane/commands_logic.cpp | 3 --- ArduPlane/is_flying.cpp | 1 - 2 files changed, 4 deletions(-) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 92268cf3ab..b5663ce822 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -22,9 +22,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) // except in a takeoff auto_state.takeoff_complete = true; - // if we are still executing mission commands then we must be traveling around still - crash_state.is_crashed = false; - // if a go around had been commanded, clear it now. auto_state.commanded_go_around = false; diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index e2849040c1..09005f8f30 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -207,7 +207,6 @@ void Plane::crash_detection_update(void) if (!crashed) { // reset timer crash_state.debounce_timer_ms = 0; - crash_state.is_crashed = false; } else if (crash_state.debounce_timer_ms == 0) { // start timer