Browse Source

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)
master
Tom Pittenger 10 years ago committed by Andrew Tridgell
parent
commit
fed50aa5c5
  1. 3
      ArduPlane/commands_logic.cpp
  2. 1
      ArduPlane/is_flying.cpp

3
ArduPlane/commands_logic.cpp

@ -22,9 +22,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) @@ -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;

1
ArduPlane/is_flying.cpp

@ -207,7 +207,6 @@ void Plane::crash_detection_update(void) @@ -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

Loading…
Cancel
Save