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/failsafe.cpp
Views: 1798
#include "Plane.h"12/*3* failsafe support4* Andrew Tridgell, December 20115*/67/*8* our failsafe strategy is to detect main loop lockup and switch to9* passing inputs straight from the RC inputs to RC outputs.10*/1112/*13* this failsafe_check function is called from the core timer interrupt14* at 1kHz.15*/16void Plane::failsafe_check(void)17{18static uint16_t last_ticks;19static uint32_t last_timestamp;20static bool in_failsafe;21uint32_t tnow = micros();2223const uint16_t ticks = scheduler.ticks();24if (ticks != last_ticks) {25// the main loop is running, all is OK26last_ticks = ticks;27last_timestamp = tnow;28in_failsafe = false;29return;30}3132if (tnow - last_timestamp > 200000) {33// we have gone at least 0.2 seconds since the main loop34// ran. That means we're in trouble, or perhaps are in35// an initialisation routine or log erase. Start passing RC36// inputs through to outputs37in_failsafe = true;38}3940if (in_failsafe && tnow - last_timestamp > 20000) {4142// ensure we have the latest RC inputs43rc().read_input();4445last_timestamp = tnow;4647rc().read_input();4849#if AP_ADVANCEDFAILSAFE_ENABLED50if (in_calibration) {51// tell the failsafe system that we are calibrating52// sensors, so don't trigger failsafe53afs.heartbeat();54}55#endif5657if (RC_Channels::get_valid_channel_count() < 5) {58// we don't have any RC input to pass through59return;60}6162// pass RC inputs to outputs every 20ms63RC_Channels::clear_overrides();6465float roll = roll_in_expo(false);66float pitch = pitch_in_expo(false);67float throttle = get_throttle_input(true);68float rudder = rudder_in_expo(false);6970if (!arming.is_armed_and_safety_off()) {71throttle = 0;72}7374// setup secondary output channels that don't have75// corresponding input channels76SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll);77SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitch);78SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);79SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);80SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle);8182// this is to allow the failsafe module to deliberately crash83// the plane. Only used in extreme circumstances to meet the84// OBC rules85#if AP_ADVANCEDFAILSAFE_ENABLED86if (afs.should_crash_vehicle()) {87afs.terminate_vehicle();88if (!afs.terminating_vehicle_via_landing()) {89return;90}91}92#endif9394// setup secondary output channels that do have95// corresponding input channels96SRV_Channels::copy_radio_in_out(SRV_Channel::k_manual, true);97SRV_Channels::set_output_scaled(SRV_Channel::k_flap, 0.0);98SRV_Channels::set_output_scaled(SRV_Channel::k_flap_auto, 0.0);99100// setup flaperons101flaperon_update();102103servos_output();104105// in SITL we send through the servo outputs so we can verify106// we're manipulating surfaces107#if CONFIG_HAL_BOARD == HAL_BOARD_SITL108GCS_MAVLINK *chan = gcs().chan(0);109if (HAVE_PAYLOAD_SPACE(chan->get_chan(), SERVO_OUTPUT_RAW)) {110chan->send_servo_output_raw();111}112#endif113}114}115116117