mirror of https://github.com/ArduPilot/ardupilot
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)
This commit is contained in:
parent
e1d566f9e7
commit
fed50aa5c5
|
@ -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;
|
||||
|
||||
|
|
|
@ -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…
Reference in New Issue