mirror of https://github.com/ArduPilot/ardupilot
AP_AdvancedFailsafe: rename from APM_OBC
This commit is contained in:
parent
636188014d
commit
cef4635ad9
|
@ -15,13 +15,13 @@
|
|||
*/
|
||||
|
||||
/*
|
||||
APM_OBC.cpp
|
||||
AP_AdvancedFailsafe.cpp
|
||||
|
||||
Outback Challenge Failsafe module
|
||||
|
||||
*/
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "APM_OBC.h"
|
||||
#include "AP_AdvancedFailsafe.h"
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <RC_Channel/RC_Channel_aux.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
@ -29,75 +29,75 @@
|
|||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo APM_OBC::var_info[] = {
|
||||
const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
|
||||
// @Param: ENABLE
|
||||
// @DisplayName: Enable Advanced Failsafe
|
||||
// @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 11, APM_OBC, _enable, 0, AP_PARAM_FLAG_ENABLE),
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 11, AP_AdvancedFailsafe, _enable, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param: MAN_PIN
|
||||
// @DisplayName: Manual Pin
|
||||
// @Description: This sets a digital output pin to set high when in manual mode
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAN_PIN", 0, APM_OBC, _manual_pin, -1),
|
||||
AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
|
||||
|
||||
// @Param: HB_PIN
|
||||
// @DisplayName: Heartbeat Pin
|
||||
// @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("HB_PIN", 1, APM_OBC, _heartbeat_pin, -1),
|
||||
AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
|
||||
|
||||
// @Param: WP_COMMS
|
||||
// @DisplayName: Comms Waypoint
|
||||
// @Description: Waypoint number to navigate to on comms loss
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WP_COMMS", 2, APM_OBC, _wp_comms_hold, 0),
|
||||
AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),
|
||||
|
||||
// @Param: GPS_LOSS
|
||||
// @DisplayName: GPS Loss Waypoint
|
||||
// @Description: Waypoint number to navigate to on GPS lock loss
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WP_GPS_LOSS", 4, APM_OBC, _wp_gps_loss, 0),
|
||||
AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),
|
||||
|
||||
// @Param: TERMINATE
|
||||
// @DisplayName: Force Terminate
|
||||
// @Description: Can be set in flight to force termination of the heartbeat signal
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERMINATE", 5, APM_OBC, _terminate, 0),
|
||||
AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),
|
||||
|
||||
// @Param: TERM_ACTION
|
||||
// @DisplayName: Terminate action
|
||||
// @Description: This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup APM to handle it here. If set to 0 (which is the default) then no extra action is taken. If set to the magic value 42 then the plane will deliberately crash itself by setting maximum throws on all surfaces, and zero throttle
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERM_ACTION", 6, APM_OBC, _terminate_action, 0),
|
||||
AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
|
||||
|
||||
// @Param: TERM_PIN
|
||||
// @DisplayName: Terminate Pin
|
||||
// @Description: This sets a digital output pin to set high on flight termination
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERM_PIN", 7, APM_OBC, _terminate_pin, -1),
|
||||
AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),
|
||||
|
||||
// @Param: AMSL_LIMIT
|
||||
// @DisplayName: AMSL limit
|
||||
// @Description: This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
|
||||
// @User: Advanced
|
||||
// @Units: meters
|
||||
AP_GROUPINFO("AMSL_LIMIT", 8, APM_OBC, _amsl_limit, 0),
|
||||
AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),
|
||||
|
||||
// @Param: AMSL_ERR_GPS
|
||||
// @DisplayName: Error margin for GPS based AMSL limit
|
||||
// @Description: This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
|
||||
// @User: Advanced
|
||||
// @Units: meters
|
||||
AP_GROUPINFO("AMSL_ERR_GPS", 9, APM_OBC, _amsl_margin_gps, -1),
|
||||
AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),
|
||||
|
||||
// @Param: QNH_PRESSURE
|
||||
// @DisplayName: QNH pressure
|
||||
// @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
|
||||
// @Units: millibar
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("QNH_PRESSURE", 10, APM_OBC, _qnh_pressure, 0),
|
||||
AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),
|
||||
|
||||
// *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE
|
||||
|
||||
|
@ -107,44 +107,44 @@ const AP_Param::GroupInfo APM_OBC::var_info[] = {
|
|||
// @DisplayName: Maximum number of GPS loss events
|
||||
// @Description: Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAX_GPS_LOSS", 13, APM_OBC, _max_gps_loss, 0),
|
||||
AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),
|
||||
|
||||
// @Param: MAX_COM_LOSS
|
||||
// @DisplayName: Maximum number of comms loss events
|
||||
// @Description: Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAX_COM_LOSS", 14, APM_OBC, _max_comms_loss, 0),
|
||||
AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),
|
||||
|
||||
// @Param: GEOFENCE
|
||||
// @DisplayName: Enable geofence Advanced Failsafe
|
||||
// @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GEOFENCE", 15, APM_OBC, _enable_geofence_fs, 1),
|
||||
AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),
|
||||
|
||||
// @Param: RC
|
||||
// @DisplayName: Enable RC Advanced Failsafe
|
||||
// @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC", 16, APM_OBC, _enable_RC_fs, 1),
|
||||
AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),
|
||||
|
||||
// @Param: RC_MAN_ONLY
|
||||
// @DisplayName: Enable RC Termination only in manual control modes
|
||||
// @Description: If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_MAN_ONLY", 17, APM_OBC, _rc_term_manual_only, 1),
|
||||
AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),
|
||||
|
||||
// @Param: DUAL_LOSS
|
||||
// @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
|
||||
// @Description: This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DUAL_LOSS", 18, APM_OBC, _enable_dual_loss, 1),
|
||||
AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),
|
||||
|
||||
// @Param: RC_FAIL_TIME
|
||||
// @DisplayName: RC failure time
|
||||
// @Description: This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
|
||||
// @User: Advanced
|
||||
// @Units: seconds
|
||||
AP_GROUPINFO("RC_FAIL_TIME", 19, APM_OBC, _rc_fail_time_seconds, 0),
|
||||
AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -152,7 +152,7 @@ const AP_Param::GroupInfo APM_OBC::var_info[] = {
|
|||
// check for Failsafe conditions. This is called at 10Hz by the main
|
||||
// ArduPlane code
|
||||
void
|
||||
APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
|
||||
AP_AdvancedFailsafe::check(AP_AdvancedFailsafe::control_mode mode, uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
|
||||
{
|
||||
if (!_enable) {
|
||||
return;
|
||||
|
@ -293,7 +293,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
|
||||
// send heartbeat messages during sensor calibration
|
||||
void
|
||||
APM_OBC::heartbeat(void)
|
||||
AP_AdvancedFailsafe::heartbeat(void)
|
||||
{
|
||||
if (!_enable) {
|
||||
return;
|
||||
|
@ -310,7 +310,7 @@ APM_OBC::heartbeat(void)
|
|||
|
||||
// check for altitude limit breach
|
||||
bool
|
||||
APM_OBC::check_altlimit(void)
|
||||
AP_AdvancedFailsafe::check_altlimit(void)
|
||||
{
|
||||
if (!_enable) {
|
||||
return false;
|
||||
|
@ -346,7 +346,7 @@ APM_OBC::check_altlimit(void)
|
|||
/*
|
||||
setup the IO boards failsafe values for if the FMU firmware crashes
|
||||
*/
|
||||
void APM_OBC::setup_failsafe(void)
|
||||
void AP_AdvancedFailsafe::setup_failsafe(void)
|
||||
{
|
||||
if (!_enable) {
|
||||
return;
|
||||
|
@ -377,7 +377,7 @@ void APM_OBC::setup_failsafe(void)
|
|||
setu radio_out values for all channels to termination values if we
|
||||
are terminating
|
||||
*/
|
||||
void APM_OBC::check_crash_plane(void)
|
||||
void AP_AdvancedFailsafe::check_crash_plane(void)
|
||||
{
|
||||
if (!_enable) {
|
||||
return;
|
|
@ -30,7 +30,7 @@
|
|||
#include <inttypes.h>
|
||||
|
||||
|
||||
class APM_OBC
|
||||
class AP_AdvancedFailsafe
|
||||
{
|
||||
public:
|
||||
enum control_mode {
|
||||
|
@ -47,7 +47,7 @@ public:
|
|||
};
|
||||
|
||||
// Constructor
|
||||
APM_OBC(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
|
||||
AP_AdvancedFailsafe(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
|
||||
mission(_mission),
|
||||
baro(_baro),
|
||||
gps(_gps),
|
||||
|
@ -133,5 +133,5 @@ private:
|
|||
bool check_altlimit(void);
|
||||
};
|
||||
|
||||
// map from ArduPlane control_mode to APM_OBC::control_mode
|
||||
#define OBC_MODE(control_mode) (auto_throttle_mode?APM_OBC::OBC_AUTO:(control_mode==MANUAL?APM_OBC::OBC_MANUAL:APM_OBC::OBC_FBW))
|
||||
// map from ArduPlane control_mode to AP_AdvancedFailsafe::control_mode
|
||||
#define OBC_MODE(control_mode) (auto_throttle_mode?AP_AdvancedFailsafe::OBC_AUTO:(control_mode==MANUAL?AP_AdvancedFailsafe::OBC_MANUAL:AP_AdvancedFailsafe::OBC_FBW))
|
Loading…
Reference in New Issue