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/ArduCopter/crash_check.cpp
Views: 1798
#include "Copter.h"12// Code to detect a crash main ArduCopter code3#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash4#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond target angle is signal we are out of control5#define CRASH_CHECK_ANGLE_MIN_DEG 15.0f // vehicle must be leaning at least 15deg to trigger crash check6#define CRASH_CHECK_SPEED_MAX 10.0f // vehicle must be moving at less than 10m/s to trigger crash check7#define CRASH_CHECK_ACCEL_MAX 3.0f // vehicle must be accelerating less than 3m/s/s to be considered crashed89// Code to detect a thrust loss main ArduCopter code10#define THRUST_LOSS_CHECK_TRIGGER_SEC 1 // 1 second descent while level and high throttle indicates thrust loss11#define THRUST_LOSS_CHECK_ANGLE_DEVIATION_CD 1500 // we can't expect to maintain altitude beyond 15 degrees on all aircraft12#define THRUST_LOSS_CHECK_MINIMUM_THROTTLE 0.9f // we can expect to maintain altitude above 90 % throttle1314// Yaw imbalance check15#define YAW_IMBALANCE_IMAX_THRESHOLD 0.75f16#define YAW_IMBALANCE_WARN_MS 100001718// crash_check - disarms motors if a crash has been detected19// crashes are detected by the vehicle being more than 20 degrees beyond it's angle limits continuously for more than 1 second20// called at MAIN_LOOP_RATE21void Copter::crash_check()22{23static uint16_t crash_counter; // number of iterations vehicle may have been crashed2425// return immediately if disarmed, or crash checking disabled26if (!motors->armed() || ap.land_complete || g.fs_crash_check == 0) {27crash_counter = 0;28return;29}3031// exit immediately if in standby32if (standby_active) {33crash_counter = 0;34return;35}3637// exit immediately if in force flying38if (get_force_flying() && !flightmode->is_landing()) {39crash_counter = 0;40return;41}4243// return immediately if we are not in an angle stabilize flight mode or we are flipping44if (!flightmode->crash_check_enabled()) {45crash_counter = 0;46return;47}4849#if MODE_AUTOROTATE_ENABLED50//return immediately if in autorotation mode51if (flightmode->mode_number() == Mode::Number::AUTOROTATE) {52crash_counter = 0;53return;54}55#endif5657// vehicle not crashed if 1hz filtered acceleration is more than 3m/s (1G on Z-axis has been subtracted)58const float filtered_acc = land_accel_ef_filter.get().length();59if (filtered_acc >= CRASH_CHECK_ACCEL_MAX) {60crash_counter = 0;61return;62}6364// check for lean angle over 15 degrees65const float lean_angle_deg = degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()));66if (lean_angle_deg <= CRASH_CHECK_ANGLE_MIN_DEG) {67crash_counter = 0;68return;69}7071// check for angle error over 30 degrees72const float angle_error = attitude_control->get_att_error_angle_deg();73if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {74crash_counter = 0;75return;76}7778// check for speed under 10m/s (if available)79Vector3f vel_ned;80if (ahrs.get_velocity_NED(vel_ned) && (vel_ned.length() >= CRASH_CHECK_SPEED_MAX)) {81crash_counter = 0;82return;83}8485// we may be crashing86crash_counter++;8788// check if crashing for 2 seconds89if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {90LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);91// send message to gcs92gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming: AngErr=%.0f>%.0f, Accel=%.1f<%.1f", angle_error, CRASH_CHECK_ANGLE_DEVIATION_DEG, filtered_acc, CRASH_CHECK_ACCEL_MAX);93// disarm motors94copter.arming.disarm(AP_Arming::Method::CRASH);95}96}9798// check for loss of thrust and trigger thrust boost in motors library99void Copter::thrust_loss_check()100{101static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed102103// no-op if suppressed by flight options param104if (copter.option_is_enabled(FlightOption::DISABLE_THRUST_LOSS_CHECK)) {105return;106}107108// exit immediately if thrust boost is already engaged109if (motors->get_thrust_boost()) {110return;111}112113// return immediately if disarmed114if (!motors->armed() || ap.land_complete) {115thrust_loss_counter = 0;116return;117}118119// exit immediately if in standby120if (standby_active) {121return;122}123124// check for desired angle over 15 degrees125// todo: add thrust angle to AC_AttitudeControl126const Vector3f angle_target = attitude_control->get_att_target_euler_cd();127if (sq(angle_target.x) + sq(angle_target.y) > sq(THRUST_LOSS_CHECK_ANGLE_DEVIATION_CD)) {128thrust_loss_counter = 0;129return;130}131132// check for throttle over 90% or throttle saturation133if ((attitude_control->get_throttle_in() < THRUST_LOSS_CHECK_MINIMUM_THROTTLE) && (!motors->limit.throttle_upper)) {134thrust_loss_counter = 0;135return;136}137138// check throttle is over 25% to prevent checks triggering from thrust limitations caused by low commanded throttle139if ((attitude_control->get_throttle_in() < 0.25f)) {140thrust_loss_counter = 0;141return;142}143144// check for descent145if (!is_negative(inertial_nav.get_velocity_z_up_cms())) {146thrust_loss_counter = 0;147return;148}149150// check for angle error over 30 degrees to ensure the aircraft has attitude control151const float angle_error = attitude_control->get_att_error_angle_deg();152if (angle_error >= CRASH_CHECK_ANGLE_DEVIATION_DEG) {153thrust_loss_counter = 0;154return;155}156157// the aircraft is descending with low requested roll and pitch, at full available throttle, with attitude control158// we may have lost thrust159thrust_loss_counter++;160161// check if thrust loss for 1 second162if (thrust_loss_counter >= (THRUST_LOSS_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {163// reset counter164thrust_loss_counter = 0;165LOGGER_WRITE_ERROR(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED);166// send message to gcs167gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1);168// enable thrust loss handling169motors->set_thrust_boost(true);170// the motors library disables this when it is no longer needed to achieve the commanded output171172#if AP_GRIPPER_ENABLED173if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) {174gripper.release();175}176#endif177}178}179180// check for a large yaw imbalance, could be due to badly calibrated ESC or misaligned motors181void Copter::yaw_imbalance_check()182{183// no-op if suppressed by flight options param184if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) {185return;186}187188// If I is disabled it is unlikely that the issue is not obvious189if (!is_positive(attitude_control->get_rate_yaw_pid().kI())) {190return;191}192193// thrust loss is triggered, yaw issues are expected194if (motors->get_thrust_boost()) {195yaw_I_filt.reset(0.0f);196return;197}198199// return immediately if disarmed200if (!motors->armed() || ap.land_complete) {201yaw_I_filt.reset(0.0f);202return;203}204205// exit immediately if in standby206if (standby_active) {207yaw_I_filt.reset(0.0f);208return;209}210211// magnitude of low pass filtered I term212const float I_term = attitude_control->get_rate_yaw_pid().get_pid_info().I;213const float I = fabsf(yaw_I_filt.apply(attitude_control->get_rate_yaw_pid().get_pid_info().I,G_Dt));214if (I > fabsf(I_term)) {215// never allow to be larger than I216yaw_I_filt.reset(I_term);217}218219const float I_max = attitude_control->get_rate_yaw_pid().imax();220if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max))))) {221// filtered using over percentage of I max or unfiltered = I max222// I makes up more than percentage of total available control power223const uint32_t now = millis();224if (now - last_yaw_warn_ms > YAW_IMBALANCE_WARN_MS) {225last_yaw_warn_ms = now;226gcs().send_text(MAV_SEVERITY_EMERGENCY, "Yaw Imbalance %0.0f%%", I *100);227}228}229}230231#if HAL_PARACHUTE_ENABLED232233// Code to detect a crash main ArduCopter code234#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute235#define PARACHUTE_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees off from target indicates a loss of control236237// parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected238// vehicle is considered to have a "serious loss of control" by the vehicle being more than 30 degrees off from the target roll and pitch angles continuously for 1 second239// called at MAIN_LOOP_RATE240void Copter::parachute_check()241{242static uint16_t control_loss_count; // number of iterations we have been out of control243static int32_t baro_alt_start;244245// exit immediately if parachute is not enabled246if (!parachute.enabled()) {247return;248}249250// pass is_flying to parachute library251parachute.set_is_flying(!ap.land_complete);252253// pass sink rate to parachute library254parachute.set_sink_rate(-inertial_nav.get_velocity_z_up_cms() * 0.01f);255256// exit immediately if in standby257if (standby_active) {258return;259}260261// call update to give parachute a chance to move servo or relay back to off position262parachute.update();263264// return immediately if motors are not armed or pilot's throttle is above zero265if (!motors->armed()) {266control_loss_count = 0;267return;268}269270if (parachute.release_initiated()) {271return;272}273274// return immediately if we are not in an angle stabilize flight mode or we are flipping275if (!flightmode->crash_check_enabled()) {276control_loss_count = 0;277return;278}279280// ensure we are flying281if (ap.land_complete) {282control_loss_count = 0;283return;284}285286// ensure the first control_loss event is from above the min altitude287if (control_loss_count == 0 && parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100)) {288return;289}290291// trigger parachute release based on sink rate292parachute.check_sink_rate();293294// check for angle error over 30 degrees295const float angle_error = attitude_control->get_att_error_angle_deg();296if (angle_error <= PARACHUTE_CHECK_ANGLE_DEVIATION_DEG) {297if (control_loss_count > 0) {298control_loss_count--;299}300return;301}302303// increment counter304if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {305control_loss_count++;306}307308// record baro alt if we have just started losing control309if (control_loss_count == 1) {310baro_alt_start = baro_alt;311312// exit if baro altitude change indicates we are not falling313} else if (baro_alt >= baro_alt_start) {314control_loss_count = 0;315return;316317// To-Do: add check that the vehicle is actually falling318319// check if loss of control for at least 1 second320} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {321// reset control loss counter322control_loss_count = 0;323LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL);324// release parachute325parachute_release();326}327}328329// parachute_release - trigger the release of the parachute, disarm the motors and notify the user330void Copter::parachute_release()331{332// release parachute333parachute.release();334335#if AP_LANDINGGEAR_ENABLED336// deploy landing gear337landinggear.set_position(AP_LandingGear::LandingGear_Deploy);338#endif339}340341// parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error342// checks if the vehicle is landed343void Copter::parachute_manual_release()344{345// exit immediately if parachute is not enabled346if (!parachute.enabled()) {347return;348}349350// do not release if vehicle is landed351// do not release if we are landed or below the minimum altitude above home352if (ap.land_complete) {353// warn user of reason for failure354gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed");355LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED);356return;357}358359// do not release if we are landed or below the minimum altitude above home360if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {361// warn user of reason for failure362gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");363LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW);364return;365}366367// if we get this far release parachute368parachute_release();369}370371#endif // HAL_PARACHUTE_ENABLED372373374