From e55350a5d657f41052fe328b947ec1e3ab5b9fa1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 16 Mar 2015 10:59:40 +1100 Subject: [PATCH] Plane: added crash detection in autoland if we are no longer flying then flare, which turns off the motor This is based on work by Tom Pittenger --- ArduPlane/landing.pde | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ArduPlane/landing.pde b/ArduPlane/landing.pde index f7f9cef21f..13ee02d1e7 100644 --- a/ArduPlane/landing.pde +++ b/ArduPlane/landing.pde @@ -52,11 +52,16 @@ static bool verify_land() */ if (height <= g.land_flare_alt || height <= auto_state.land_sink_rate * aparm.land_flare_sec || - (!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc))) { + (!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) || + (fabsf(auto_state.land_sink_rate) < 0.2f && !is_flying())) { if (!auto_state.land_complete) { - gcs_send_text_fmt(PSTR("Flare %.1fm sink=%.2f speed=%.1f"), - height, auto_state.land_sink_rate, gps.ground_speed()); + if (!is_flying()) { + gcs_send_text_fmt(PSTR("Flare crash detected: speed=%.1f"), gps.ground_speed()); + } else { + gcs_send_text_fmt(PSTR("Flare %.1fm sink=%.2f speed=%.1f"), + height, auto_state.land_sink_rate, gps.ground_speed()); + } } auto_state.land_complete = true;