APM:Libraries
AP_AdvancedFailsafe.h
Go to the documentation of this file.
1 #pragma once
2 
3 /*
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 /*
18  Outback Challenge Failsafe module
19 
20  Andrew Tridgell and CanberraUAV, August 2012
21 */
22 
23 #include <AP_Common/AP_Common.h>
24 #include <AP_Param/AP_Param.h>
25 #include <AP_Mission/AP_Mission.h>
26 #include <AP_Baro/AP_Baro.h>
27 #include <AP_GPS/AP_GPS.h>
29 #include <inttypes.h>
30 
31 
33 {
34 public:
35  enum control_mode {
39  };
40 
41  enum state {
46  };
47 
51  };
52 
53  // Constructor
54  AP_AdvancedFailsafe(AP_Mission &_mission, const AP_GPS &_gps) :
55  mission(_mission),
56  gps(_gps),
57  _gps_loss_count(0),
59  {
61 
63  _terminate.set(0);
64 
65  _saved_wp = 0;
66  }
67 
68  // check that everything is OK
69  void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms);
70 
71  // generate heartbeat msgs, so external failsafe boards are happy
72  // during sensor calibration
73  void heartbeat(void);
74 
75  // return true if we are terminating (deliberately crashing the vehicle)
76  bool should_crash_vehicle(void);
77 
78  // enables or disables a GCS based termination, returns true if AFS is in the desired termination state
79  bool gcs_terminate(bool should_terminate, const char *reason);
80 
81  // called to set all outputs to termination state
82  virtual void terminate_vehicle(void) = 0;
83 
84  // for holding parameters
85  static const struct AP_Param::GroupInfo var_info[];
86 
87 protected:
88  // setup failsafe values for if FMU firmware stops running
89  virtual void setup_IO_failsafe(void) = 0;
90 
91  // return the AFS mapped control mode
92  virtual enum control_mode afs_mode(void) = 0;
93 
94  enum state _state;
95 
97  const AP_GPS &gps;
98 
99  AP_Int8 _enable;
100  // digital output pins for communicating with the failsafe board
101  AP_Int8 _heartbeat_pin;
102  AP_Int8 _manual_pin;
103  AP_Int8 _terminate_pin;
104  AP_Int8 _terminate;
106 
107  // waypoint numbers to jump to on failsafe conditions
108  AP_Int8 _wp_comms_hold;
109  AP_Int8 _wp_gps_loss;
110 
111  AP_Float _qnh_pressure;
112  AP_Int32 _amsl_limit;
115  AP_Int8 _max_gps_loss;
118  AP_Int8 _enable_RC_fs;
121 
123 
124  // saved waypoint for resuming mission
125  uint8_t _saved_wp;
126 
127  // number of times we've lost GPS
129 
130  // number of times we've lost data link
132 
133  // last comms loss time
135 
136  // last GPS loss time
138 
139  // have the failsafe values been setup?
141 
142  bool check_altlimit(void);
143 };
Definition: AP_GPS.h:48
bool gcs_terminate(bool should_terminate, const char *reason)
virtual enum control_mode afs_mode(void)=0
Object managing Mission.
Definition: AP_Mission.h:45
A system for managing and storing variables that are of general interest to the system.
virtual void setup_IO_failsafe(void)=0
virtual void terminate_vehicle(void)=0
AP_AdvancedFailsafe(AP_Mission &_mission, const AP_GPS &_gps)
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
static const struct AP_Param::GroupInfo var_info[]
Common definitions and utility routines for the ArduPilot libraries.
void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214