|
|
@ -70,6 +70,10 @@ void Plane::update_is_flying_5Hz(void) |
|
|
|
crash_state.impact_detected = false; |
|
|
|
crash_state.impact_detected = false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) { |
|
|
|
|
|
|
|
is_flying_bool = true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
switch (flight_stage) |
|
|
|
switch (flight_stage) |
|
|
|
{ |
|
|
|
{ |
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: |
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: |
|
|
@ -89,16 +93,6 @@ void Plane::update_is_flying_5Hz(void) |
|
|
|
// TODO: detect ground impacts
|
|
|
|
// TODO: detect ground impacts
|
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH: |
|
|
|
|
|
|
|
if (fabsf(auto_state.sink_rate) > 0.2f) { |
|
|
|
|
|
|
|
is_flying_bool = true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE: |
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL: |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND: |
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND: |
|
|
|
if (auto_state.sink_rate < -0.5f) { |
|
|
|
if (auto_state.sink_rate < -0.5f) { |
|
|
|
// steep climb
|
|
|
|
// steep climb
|
|
|
@ -114,9 +108,7 @@ void Plane::update_is_flying_5Hz(void) |
|
|
|
// when disarmed assume not flying and need overwhelming evidence that we ARE flying
|
|
|
|
// when disarmed assume not flying and need overwhelming evidence that we ARE flying
|
|
|
|
is_flying_bool = airspeed_movement && gps_confirmed_movement; |
|
|
|
is_flying_bool = airspeed_movement && gps_confirmed_movement; |
|
|
|
|
|
|
|
|
|
|
|
if ((control_mode == AUTO) && |
|
|
|
if ((flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF) || landing.is_flaring()) { |
|
|
|
((flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF) || |
|
|
|
|
|
|
|
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL)) ) { |
|
|
|
|
|
|
|
is_flying_bool = false; |
|
|
|
is_flying_bool = false; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -205,6 +197,39 @@ void Plane::crash_detection_update(void) |
|
|
|
|
|
|
|
|
|
|
|
if (!is_flying() && arming.is_armed()) |
|
|
|
if (!is_flying() && arming.is_armed()) |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
if (landing.is_expecting_impact()) { |
|
|
|
|
|
|
|
// We should be nice and level-ish in this flight stage. If not, we most
|
|
|
|
|
|
|
|
// likely had a crazy landing. Throttle is inhibited already at the flare
|
|
|
|
|
|
|
|
// but go ahead and notify GCS and perform any additional post-crash actions.
|
|
|
|
|
|
|
|
// Declare a crash if we are oriented more that 60deg in pitch or roll
|
|
|
|
|
|
|
|
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 = |
|
|
|
|
|
|
|
get_distance(current_loc, mission.get_current_nav_cmd().content.location) < 75; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// 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.checkedHardLanding = true; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else if (landing.is_on_approach()) { |
|
|
|
|
|
|
|
// when altitude gets low, we automatically flare so ground crashes
|
|
|
|
|
|
|
|
// most likely can not be triggered from here. However,
|
|
|
|
|
|
|
|
// a crash into a tree would be caught here.
|
|
|
|
|
|
|
|
if (been_auto_flying) { |
|
|
|
|
|
|
|
crashed = true; |
|
|
|
|
|
|
|
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
switch (flight_stage) |
|
|
|
switch (flight_stage) |
|
|
|
{ |
|
|
|
{ |
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: |
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: |
|
|
@ -231,44 +256,10 @@ void Plane::crash_detection_update(void) |
|
|
|
crashed = false; |
|
|
|
crashed = false; |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH: |
|
|
|
|
|
|
|
if (been_auto_flying) { |
|
|
|
|
|
|
|
crashed = true; |
|
|
|
|
|
|
|
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
// when altitude gets low, we automatically progress to FLIGHT_LAND_FINAL
|
|
|
|
|
|
|
|
// so ground crashes most likely can not be triggered from here. However,
|
|
|
|
|
|
|
|
// a crash into a tree would be caught here.
|
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE: |
|
|
|
|
|
|
|
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL: |
|
|
|
|
|
|
|
// We should be nice and level-ish in this flight stage. If not, we most
|
|
|
|
|
|
|
|
// likely had a crazy landing. Throttle is inhibited already at the flare
|
|
|
|
|
|
|
|
// but go ahead and notify GCS and perform any additional post-crash actions.
|
|
|
|
|
|
|
|
// Declare a crash if we are oriented more that 60deg in pitch or roll
|
|
|
|
|
|
|
|
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 = |
|
|
|
|
|
|
|
get_distance(current_loc, mission.get_current_nav_cmd().content.location) < 75; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// 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.checkedHardLanding = true; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
default: |
|
|
|
break; |
|
|
|
break; |
|
|
|
} // switch
|
|
|
|
} // switch
|
|
|
|
|
|
|
|
} |
|
|
|
} else { |
|
|
|
} else { |
|
|
|
crash_state.checkedHardLanding = false; |
|
|
|
crash_state.checkedHardLanding = false; |
|
|
|
} |
|
|
|
} |
|
|
|