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/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h
Views: 1798
#pragma once12/*3This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/16/*17Outback Challenge Failsafe module1819Andrew Tridgell and CanberraUAV, August 201220*/2122#include "AP_AdvancedFailsafe_config.h"2324#if AP_ADVANCEDFAILSAFE_ENABLED2526#include <AP_Common/AP_Common.h>27#include <AP_Param/AP_Param.h>28#include <inttypes.h>29#include <AP_Common/Location.h>3031class AP_AdvancedFailsafe32{33public:34enum control_mode {35AFS_MANUAL = 0,36AFS_STABILIZED = 1,37AFS_AUTO = 238};3940enum state {41STATE_PREFLIGHT = 0,42STATE_AUTO = 1,43STATE_DATA_LINK_LOSS = 2,44STATE_GPS_LOSS = 345};4647enum terminate_action {48TERMINATE_ACTION_TERMINATE = 42,49TERMINATE_ACTION_LAND = 4350};5152/* Do not allow copies */53CLASS_NO_COPY(AP_AdvancedFailsafe);5455// Constructor56AP_AdvancedFailsafe()57{58AP_Param::setup_object_defaults(this, var_info);59if (_singleton != nullptr) {60AP_HAL::panic("AP_AdvancedFailsafe must be singleton");61}6263_singleton = this;64_state = STATE_PREFLIGHT;65_terminate.set(0);6667_saved_wp = 0;68}6970// get singleton instance71static AP_AdvancedFailsafe *get_singleton(void) {72return _singleton;73}7475bool enabled() { return _enable; }7677// check that everything is OK78void check(uint32_t last_valid_rc_ms);7980// generate heartbeat msgs, so external failsafe boards are happy81// during sensor calibration82void heartbeat(void);8384// return true if we are terminating (deliberately crashing the vehicle)85bool should_crash_vehicle(void);8687// enables or disables a GCS based termination, returns true if AFS is in the desired termination state88bool gcs_terminate(bool should_terminate, const char *reason);8990// called to set all outputs to termination state91virtual void terminate_vehicle(void) = 0;9293// for holding parameters94static const struct AP_Param::GroupInfo var_info[];9596bool terminating_vehicle_via_landing() const {97return _terminate_action == TERMINATE_ACTION_LAND;98};99100protected:101// setup failsafe values for if FMU firmware stops running102virtual void setup_IO_failsafe(void) = 0;103104// return the AFS mapped control mode105virtual enum control_mode afs_mode(void) = 0;106107//to force entering auto mode when datalink loss108virtual void set_mode_auto(void) = 0;109110enum state _state;111112AP_Int8 _enable;113// digital output pins for communicating with the failsafe board114AP_Int8 _heartbeat_pin;115AP_Int8 _manual_pin;116AP_Int8 _terminate_pin;117AP_Int8 _terminate;118AP_Int8 _terminate_action;119120// waypoint numbers to jump to on failsafe conditions121AP_Int8 _wp_comms_hold;122AP_Int8 _wp_gps_loss;123124AP_Float _qnh_pressure;125AP_Int32 _amsl_limit;126AP_Int32 _amsl_margin_gps;127AP_Float _rc_fail_time_seconds;128AP_Float _gcs_fail_time_seconds;129AP_Int8 _max_gps_loss;130AP_Int8 _max_comms_loss;131AP_Int8 _enable_geofence_fs;132AP_Int8 _enable_RC_fs;133AP_Int8 _rc_term_manual_only;134AP_Int8 _enable_dual_loss;135AP_Int16 _max_range_km;136137bool _heartbeat_pin_value;138139// saved waypoint for resuming mission140uint8_t _saved_wp;141142// number of times we've lost GPS143uint8_t _gps_loss_count;144145// number of times we've lost data link146uint8_t _comms_loss_count;147148// last comms loss time149uint32_t _last_comms_loss_ms;150151// last GPS loss time152uint32_t _last_gps_loss_ms;153154// have the failsafe values been setup?155bool _failsafe_setup:1;156157Location _first_location;158bool _have_first_location;159uint32_t _term_range_notice_ms;160161bool check_altlimit(void);162163private:164static AP_AdvancedFailsafe *_singleton;165166// update maximum range check167void max_range_update();168169AP_Int16 options;170enum class Option {171CONTINUE_AFTER_RECOVERED = (1U<<0),172GCS_FS_ALL_AUTONOMOUS_MODES = (1U<<1),173};174bool option_is_set(Option option) const {175return (options.get() & int16_t(option)) != 0;176}177};178179namespace AP {180AP_AdvancedFailsafe *advancedfailsafe();181};182183#endif // AP_ADVANCEDFAILSAFE_ENABLED184185186