Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/is_flying.cpp
Views: 1798
#include "Plane.h"12#include <AP_Stats/AP_Stats.h> // statistics library34/*5is_flying and crash detection logic6*/78#define CRASH_DETECTION_DELAY_MS 5009#define IS_FLYING_IMPACT_TIMER_MS 300010#define GPS_IS_FLYING_SPEED_CMS 1501112/*13Do we think we are flying?14Probabilistic method where a bool is low-passed and considered a probability.15*/16void Plane::update_is_flying_5Hz(void)17{18float aspeed=0;19bool is_flying_bool = false;20uint32_t now_ms = AP_HAL::millis();2122uint32_t ground_speed_thresh_cm = (aparm.min_groundspeed > 0) ? ((uint32_t)(aparm.min_groundspeed*(100*0.9))) : GPS_IS_FLYING_SPEED_CMS;23bool gps_confirmed_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_3D) &&24(gps.ground_speed_cm() >= ground_speed_thresh_cm);2526// airspeed at least 75% of stall speed?27const float airspeed_threshold = MAX(aparm.airspeed_min,2)*0.75f;28bool airspeed_movement = ahrs.airspeed_estimate(aspeed) && (aspeed >= airspeed_threshold);2930if (gps.status() < AP_GPS::GPS_OK_FIX_2D && arming.is_armed() && !airspeed_movement && isFlyingProbability > 0.3) {31// when flying with no GPS, use the last airspeed estimate to32// determine if we think we have airspeed movement. This33// prevents the crash detector from triggering when34// dead-reckoning under long GPS loss35airspeed_movement = aspeed >= airspeed_threshold;36}3738#if HAL_QUADPLANE_ENABLED39is_flying_bool = quadplane.is_flying();40#endif41if (is_flying_bool) {42// no need to look further43} else if(arming.is_armed()) {44// when armed assuming flying and we need overwhelming evidence that we ARE NOT flying45// short drop-outs of GPS are common during flight due to banking which points the antenna in different directions46bool gps_lost_recently = (gps.last_fix_time_ms() > 0) && // we have locked to GPS before47(gps.status() < AP_GPS::GPS_OK_FIX_2D) && // and it's lost now48(now_ms - gps.last_fix_time_ms() < 5000); // but it wasn't that long ago (<5s)4950if ((auto_state.last_flying_ms > 0) && gps_lost_recently) {51// we've flown before, remove GPS constraints temporarily and only use airspeed52is_flying_bool = airspeed_movement; // moving through the air53} else {54// Because ahrs.airspeed_estimate can return a continued high value after landing if flying in55// strong winds above stall speed it is necessary to include the IMU based movement check.56is_flying_bool = (airspeed_movement && !AP::ins().is_still()) || // moving through the air57gps_confirmed_movement; // locked and we're moving58}5960if (control_mode == &mode_auto) {61/*62make is_flying() more accurate during various auto modes63*/6465// Detect X-axis deceleration for probable ground impacts.66// Limit the max probability so it can decay faster. This67// will not change the is_flying state, anything above 0.168// is "true", it just allows it to decay faster once we decide we69// aren't flying using the normal schemes70if (g.crash_accel_threshold == 0) {71crash_state.impact_detected = false;72} else if (ins.get_accel_peak_hold_neg_x() < -(g.crash_accel_threshold)) {73// large deceleration detected, lets lower confidence VERY quickly74crash_state.impact_detected = true;75crash_state.impact_timer_ms = now_ms;76if (isFlyingProbability > 0.2f) {77isFlyingProbability = 0.2f;78}79} else if (crash_state.impact_detected &&80(now_ms - crash_state.impact_timer_ms > IS_FLYING_IMPACT_TIMER_MS)) {81// no impacts seen in a while, clear the flag so we stop clipping isFlyingProbability82crash_state.impact_detected = false;83}8485switch (flight_stage)86{87case AP_FixedWing::FlightStage::TAKEOFF:88break;8990case AP_FixedWing::FlightStage::NORMAL:91if (in_preLaunch_flight_stage()) {92// while on the ground, an uncalibrated airspeed sensor can drift to 7m/s so93// ensure we aren't showing a false positive.94is_flying_bool = false;95crash_state.is_crashed = false;96auto_state.started_flying_in_auto_ms = 0;97}98break;99100case AP_FixedWing::FlightStage::VTOL:101// TODO: detect ground impacts102break;103104case AP_FixedWing::FlightStage::LAND:105if (landing.is_on_approach() && auto_state.sink_rate > 0.2f) {106is_flying_bool = true;107}108break;109110case AP_FixedWing::FlightStage::ABORT_LANDING:111if (auto_state.sink_rate < -0.5f) {112// steep climb113is_flying_bool = true;114}115break;116117default:118break;119} // switch120}121} else {122// when disarmed assume not flying and need overwhelming evidence that we ARE flying123is_flying_bool = airspeed_movement && gps_confirmed_movement;124125if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || landing.is_flaring()) {126is_flying_bool = false;127}128}129130if (!crash_state.impact_detected || !is_flying_bool) {131// when impact is detected, enforce a clip. Only allow isFlyingProbability to go down, not up.132// low-pass the result.133// coef=0.15f @ 5Hz takes 3.0s to go from 100% down to 10% (or 0% up to 90%)134isFlyingProbability = (0.85f * isFlyingProbability) + (0.15f * (float)is_flying_bool);135}136137/*138update last_flying_ms so we always know how long we have not139been flying for. This helps for crash detection and auto-disarm140*/141bool new_is_flying = is_flying();142143// we are flying, note the time144if (new_is_flying) {145146auto_state.last_flying_ms = now_ms;147148if (!previous_is_flying) {149// just started flying in any mode150started_flying_ms = now_ms;151}152153if ((control_mode == &mode_auto) &&154((auto_state.started_flying_in_auto_ms == 0) || !previous_is_flying) ) {155156// We just started flying, note that time also157auto_state.started_flying_in_auto_ms = now_ms;158}159}160previous_is_flying = new_is_flying;161#if HAL_ADSB_ENABLED162adsb.set_is_flying(new_is_flying);163#endif164#if HAL_PARACHUTE_ENABLED165parachute.set_is_flying(new_is_flying);166#endif167#if AP_STATS_ENABLED168AP::stats()->set_flying(new_is_flying);169#endif170AP_Notify::flags.flying = new_is_flying;171172crash_detection_update();173174#if HAL_LOGGING_ENABLED175Log_Write_Status();176#endif177178// tell AHRS flying state179set_likely_flying(new_is_flying);180181// conservative ground mode value for rate D suppression182ground_mode = !is_flying() && !arming.is_armed_and_safety_off();183}184185/*186return true if we think we are flying. This is a probabilistic187estimate, and needs to be used very carefully. Each use case needs188to be thought about individually.189*/190bool Plane::is_flying(void)191{192if (arming.is_armed_and_safety_off()) {193#if HAL_QUADPLANE_ENABLED194if (quadplane.is_flying_vtol()) {195return true;196}197#endif198// when armed, assume we're flying unless we probably aren't199return (isFlyingProbability >= 0.1f);200}201202// when disarmed, assume we're not flying unless we probably are203return (isFlyingProbability >= 0.9f);204}205206/*207* Determine if we have crashed208*/209void Plane::crash_detection_update(void)210{211if (control_mode != &mode_auto || !aparm.crash_detection_enable)212{213// crash detection is only available in AUTO mode214crash_state.debounce_timer_ms = 0;215crash_state.is_crashed = false;216return;217}218219uint32_t now_ms = AP_HAL::millis();220bool crashed_near_land_waypoint = false;221bool crashed = false;222bool been_auto_flying = (auto_state.started_flying_in_auto_ms > 0) &&223(now_ms - auto_state.started_flying_in_auto_ms >= 2500);224225if (!is_flying() && arming.is_armed())226{227if (landing.is_expecting_impact()) {228// We should be nice and level-ish in this flight stage. If not, we most229// likely had a crazy landing. Throttle is inhibited already at the flare230// but go ahead and notify GCS and perform any additional post-crash actions.231// Declare a crash if we are oriented more that 60deg in pitch or roll232if (!crash_state.checkedHardLanding && // only check once233been_auto_flying &&234(labs(ahrs.roll_sensor) > 6000 || labs(ahrs.pitch_sensor) > 6000)) {235236crashed = true;237238// did we "crash" within 75m of the landing location? Probably just a hard landing239crashed_near_land_waypoint =240current_loc.get_distance(mission.get_current_nav_cmd().content.location) < 75;241242// trigger hard landing event right away, or never again. This inhibits a false hard landing243// event when, for example, a minute after a good landing you pick the plane up and244// this logic is still running and detects the plane is on its side as you carry it.245crash_state.debounce_timer_ms = now_ms;246crash_state.debounce_time_total_ms = 0; // no debounce247}248249crash_state.checkedHardLanding = true;250251} else if (landing.is_on_approach()) {252// when altitude gets low, we automatically flare so ground crashes253// most likely can not be triggered from here. However,254// a crash into a tree would be caught here.255if (been_auto_flying) {256crashed = true;257crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;258}259260} else {261switch (flight_stage)262{263case AP_FixedWing::FlightStage::TAKEOFF:264if (g.takeoff_throttle_min_accel > 0 &&265!throttle_suppressed) {266// if you have an acceleration holding back throttle, but you met the267// accel threshold but still not flying, then you either shook/hit the268// plane or it was a failed launch.269crashed = true;270crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;271}272// TODO: handle auto missions without NAV_TAKEOFF mission cmd273break;274275case AP_FixedWing::FlightStage::NORMAL:276if (!in_preLaunch_flight_stage() && been_auto_flying) {277crashed = true;278crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;279}280break;281282case AP_FixedWing::FlightStage::VTOL:283// we need a totally new method for this284crashed = false;285break;286287default:288break;289} // switch290}291} else {292crash_state.checkedHardLanding = false;293}294295// if we have no GPS lock and we don't have a functional airspeed296// sensor then don't do crash detection297if (gps.status() < AP_GPS::GPS_OK_FIX_3D) {298#if AP_AIRSPEED_ENABLED299if (!airspeed.use() || !airspeed.healthy()) {300crashed = false;301}302#else303crashed = false;304#endif305}306307if (!crashed) {308// reset timer309crash_state.debounce_timer_ms = 0;310311} else if (crash_state.debounce_timer_ms == 0) {312// start timer313crash_state.debounce_timer_ms = now_ms;314315} else if ((now_ms - crash_state.debounce_timer_ms >= crash_state.debounce_time_total_ms) && !crash_state.is_crashed) {316crash_state.is_crashed = true;317if (aparm.crash_detection_enable & CRASH_DETECT_ACTION_BITMASK_DISARM) {318arming.disarm(AP_Arming::Method::CRASH);319}320if (crashed_near_land_waypoint) {321gcs().send_text(MAV_SEVERITY_CRITICAL, "Hard landing detected");322} else {323gcs().send_text(MAV_SEVERITY_EMERGENCY, "Crash detected");324}325}326}327328/*329* return true if we are in a pre-launch phase of an auto-launch, typically used in bungee launches330*/331bool Plane::in_preLaunch_flight_stage(void)332{333if (control_mode == &mode_takeoff && throttle_suppressed) {334return true;335}336#if HAL_QUADPLANE_ENABLED337if (quadplane.is_vtol_takeoff(mission.get_current_nav_cmd().id)) {338return false;339}340#endif341return (control_mode == &mode_auto &&342throttle_suppressed &&343flight_stage == AP_FixedWing::FlightStage::NORMAL &&344mission.get_current_nav_cmd().id == MAV_CMD_NAV_TAKEOFF);345}346347348