diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index bebbb367d4..c0ed21bcb2 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -208,8 +208,8 @@ void Plane::crash_detection_update(void) if (!crash_state.checkedHardLanding && // only check once been_auto_flying && (labs(ahrs.roll_sensor) > 6000 || labs(ahrs.pitch_sensor) > 6000)) { + crashed = true; - crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS; // did we "crash" within 75m of the landing location? Probably just a hard landing crashed_near_land_waypoint = @@ -218,7 +218,8 @@ void Plane::crash_detection_update(void) // trigger hard landing event right away, or never again. This inhibits a false hard landing // event when, for example, a minute after a good landing you pick the plane up and // this logic is still running and detects the plane is on its side as you carry it. - crash_state.debounce_timer_ms = now_ms + CRASH_DETECTION_DELAY_MS; + crash_state.debounce_timer_ms = now; + crash_state.debounce_time_total_ms = 0; // no debounce } crash_state.checkedHardLanding = true;