2014-04-11 03:35:01 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2016-02-17 21:25:37 -04:00
|
|
|
#pragma once
|
2014-04-11 03:35:01 -03:00
|
|
|
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2012-07-08 22:49:26 -03:00
|
|
|
/*
|
|
|
|
Outback Challenge Failsafe module
|
|
|
|
|
|
|
|
Andrew Tridgell and CanberraUAV, August 2012
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:41 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <AP_GPS/AP_GPS.h>
|
|
|
|
#include <AP_RCMapper/AP_RCMapper.h>
|
2012-07-08 22:49:26 -03:00
|
|
|
#include <inttypes.h>
|
|
|
|
|
|
|
|
|
|
|
|
class APM_OBC
|
|
|
|
{
|
|
|
|
public:
|
2014-06-01 21:47:02 -03:00
|
|
|
enum control_mode {
|
|
|
|
OBC_MANUAL = 0,
|
|
|
|
OBC_FBW = 1,
|
|
|
|
OBC_AUTO = 2
|
|
|
|
};
|
|
|
|
|
|
|
|
enum state {
|
|
|
|
STATE_PREFLIGHT = 0,
|
|
|
|
STATE_AUTO = 1,
|
|
|
|
STATE_DATA_LINK_LOSS = 2,
|
|
|
|
STATE_GPS_LOSS = 3
|
|
|
|
};
|
|
|
|
|
|
|
|
// Constructor
|
2014-04-20 21:35:39 -03:00
|
|
|
APM_OBC(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
|
2014-04-11 03:35:01 -03:00
|
|
|
mission(_mission),
|
|
|
|
baro(_baro),
|
2014-04-20 21:35:39 -03:00
|
|
|
gps(_gps),
|
2014-08-17 05:06:42 -03:00
|
|
|
rcmap(_rcmap),
|
|
|
|
_gps_loss_count(0),
|
|
|
|
_comms_loss_count(0)
|
2014-04-11 03:35:01 -03:00
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
|
|
|
|
_state = STATE_PREFLIGHT;
|
|
|
|
_terminate.set(0);
|
|
|
|
|
|
|
|
_saved_wp = 0;
|
|
|
|
}
|
|
|
|
|
2014-09-23 22:03:19 -03:00
|
|
|
// check that everything is OK
|
2014-08-17 05:06:42 -03:00
|
|
|
void check(enum control_mode control_mode, uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms);
|
2012-07-08 22:49:26 -03:00
|
|
|
|
2014-09-23 22:03:19 -03:00
|
|
|
// generate heartbeat msgs, so external failsafe boards are happy
|
|
|
|
// during sensor calibration
|
|
|
|
void heartbeat(void);
|
|
|
|
|
2014-04-20 21:35:39 -03:00
|
|
|
// called in servo output code to set servos to crash position if needed
|
2014-06-01 21:47:02 -03:00
|
|
|
void check_crash_plane(void);
|
2012-08-28 02:51:32 -03:00
|
|
|
|
2014-06-01 21:47:02 -03:00
|
|
|
// for holding parameters
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-07-08 22:49:26 -03:00
|
|
|
|
|
|
|
private:
|
2014-06-01 21:47:02 -03:00
|
|
|
enum state _state;
|
2012-07-08 22:49:26 -03:00
|
|
|
|
2014-04-11 03:35:01 -03:00
|
|
|
AP_Mission &mission;
|
|
|
|
AP_Baro &baro;
|
|
|
|
const AP_GPS &gps;
|
2014-04-20 21:35:39 -03:00
|
|
|
const RCMapper &rcmap;
|
2014-04-11 03:35:01 -03:00
|
|
|
|
2014-08-08 00:30:00 -03:00
|
|
|
AP_Int8 _enable;
|
2014-06-01 21:47:02 -03:00
|
|
|
// digital output pins for communicating with the failsafe board
|
|
|
|
AP_Int8 _heartbeat_pin;
|
|
|
|
AP_Int8 _manual_pin;
|
|
|
|
AP_Int8 _terminate_pin;
|
|
|
|
AP_Int8 _terminate;
|
|
|
|
AP_Int8 _terminate_action;
|
2012-07-08 22:49:26 -03:00
|
|
|
|
2014-06-01 21:47:02 -03:00
|
|
|
// waypoint numbers to jump to on failsafe conditions
|
|
|
|
AP_Int8 _wp_comms_hold;
|
|
|
|
AP_Int8 _wp_gps_loss;
|
2012-07-08 22:49:26 -03:00
|
|
|
|
2014-04-11 03:35:01 -03:00
|
|
|
AP_Float _qnh_pressure;
|
|
|
|
AP_Int32 _amsl_limit;
|
|
|
|
AP_Int32 _amsl_margin_gps;
|
2016-04-22 20:03:46 -03:00
|
|
|
AP_Float _rc_fail_time_seconds;
|
2014-08-17 05:06:42 -03:00
|
|
|
AP_Int8 _max_gps_loss;
|
|
|
|
AP_Int8 _max_comms_loss;
|
2016-03-21 16:44:48 -03:00
|
|
|
AP_Int8 _enable_geofence_fs;
|
|
|
|
AP_Int8 _enable_RC_fs;
|
|
|
|
AP_Int8 _rc_term_manual_only;
|
|
|
|
AP_Int8 _enable_dual_loss;
|
2014-04-11 03:35:01 -03:00
|
|
|
|
2014-06-01 21:47:02 -03:00
|
|
|
bool _heartbeat_pin_value;
|
2012-07-08 22:49:26 -03:00
|
|
|
|
2014-06-01 21:47:02 -03:00
|
|
|
// saved waypoint for resuming mission
|
|
|
|
uint8_t _saved_wp;
|
2014-08-17 05:06:42 -03:00
|
|
|
|
|
|
|
// number of times we've lost GPS
|
|
|
|
uint8_t _gps_loss_count;
|
|
|
|
|
|
|
|
// number of times we've lost data link
|
|
|
|
uint8_t _comms_loss_count;
|
|
|
|
|
|
|
|
// last comms loss time
|
|
|
|
uint32_t _last_comms_loss_ms;
|
|
|
|
|
|
|
|
// last GPS loss time
|
|
|
|
uint32_t _last_gps_loss_ms;
|
2014-04-11 03:35:01 -03:00
|
|
|
|
2014-04-20 21:35:39 -03:00
|
|
|
// have the failsafe values been setup?
|
|
|
|
bool _failsafe_setup:1;
|
|
|
|
|
|
|
|
// setup failsafe values for if FMU firmware stops running
|
|
|
|
void setup_failsafe(void);
|
|
|
|
|
2014-06-01 21:47:02 -03:00
|
|
|
bool check_altlimit(void);
|
2012-07-08 22:49:26 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// map from ArduPlane control_mode to APM_OBC::control_mode
|
2014-08-17 05:06:42 -03:00
|
|
|
#define OBC_MODE(control_mode) (auto_throttle_mode?APM_OBC::OBC_AUTO:(control_mode==MANUAL?APM_OBC::OBC_MANUAL:APM_OBC::OBC_FBW))
|