ArduPlane: add and use AP_ADVANCEDFAILSAFE_ENABLED

This commit is contained in:
Peter Barker 2023-02-06 16:39:02 +11:00 committed by Andrew Tridgell
parent 8259f3f870
commit 648a13d3f7
10 changed files with 17 additions and 27 deletions

View File

@ -71,7 +71,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(calc_airspeed_errors, 10, 100, 42), SCHED_TASK(calc_airspeed_errors, 10, 100, 42),
SCHED_TASK(update_alt, 10, 200, 45), SCHED_TASK(update_alt, 10, 200, 45),
SCHED_TASK(adjust_altitude_target, 10, 200, 48), SCHED_TASK(adjust_altitude_target, 10, 200, 48),
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
SCHED_TASK(afs_fs_check, 10, 100, 51), SCHED_TASK(afs_fs_check, 10, 100, 51),
#endif #endif
SCHED_TASK(ekf_check, 10, 75, 54), SCHED_TASK(ekf_check, 10, 75, 54),
@ -277,7 +277,7 @@ void Plane::update_logging25(void)
/* /*
check for AFS failsafe check check for AFS failsafe check
*/ */
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
void Plane::afs_fs_check(void) void Plane::afs_fs_check(void)
{ {
afs.check(failsafe.AFS_last_valid_rc_ms); afs.check(failsafe.AFS_last_valid_rc_ms);

View File

@ -927,7 +927,7 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(sitl, "SIM_", SITL::SIM), GOBJECT(sitl, "SIM_", SITL::SIM),
#endif #endif
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
// @Group: AFS_ // @Group: AFS_
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
GOBJECT(afs, "AFS_", AP_AdvancedFailsafe), GOBJECT(afs, "AFS_", AP_AdvancedFailsafe),

View File

@ -92,7 +92,7 @@
// Configuration // Configuration
#include "config.h" #include "config.h"
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
#include "afs_plane.h" #include "afs_plane.h"
#endif #endif
@ -656,7 +656,7 @@ private:
#endif #endif
// Outback Challenge Failsafe Support // Outback Challenge Failsafe Support
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
AP_AdvancedFailsafe_Plane afs; AP_AdvancedFailsafe_Plane afs;
#endif #endif
@ -1004,7 +1004,7 @@ private:
void update_GPS_10Hz(void); void update_GPS_10Hz(void);
void update_compass(void); void update_compass(void);
void update_alt(void); void update_alt(void);
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
void afs_fs_check(void); void afs_fs_check(void);
#endif #endif
void one_second_loop(void); void one_second_loop(void);

View File

@ -4,7 +4,7 @@
#include "Plane.h" #include "Plane.h"
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
/* /*
setup radio_out values for all channels to termination values setup radio_out values for all channels to termination values
@ -103,4 +103,4 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Plane::afs_mode(void)
} }
return AP_AdvancedFailsafe::AFS_STABILIZED; return AP_AdvancedFailsafe::AFS_STABILIZED;
} }
#endif // ADVANCED_FAILSAFE #endif // AP_ADVANCEDFAILSAFE_ENABLED

View File

@ -18,7 +18,7 @@
advanced failsafe support for plane advanced failsafe support for plane
*/ */
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h> #include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
/* /*
@ -41,5 +41,4 @@ protected:
enum control_mode afs_mode(void) override; enum control_mode afs_mode(void) override;
}; };
#endif // ADVANCED_FAILSAFE #endif // AP_ADVANCEDFAILSAFE_ENABLED

View File

@ -24,15 +24,6 @@
# define MAV_SYSTEM_ID 1 # define MAV_SYSTEM_ID 1
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Advanced Failsafe support
//
#ifndef ADVANCED_FAILSAFE
# define ADVANCED_FAILSAFE ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION // RADIO CONFIGURATION

View File

@ -275,7 +275,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
} }
case Failsafe_Action_Terminate: case Failsafe_Action_Terminate:
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
char battery_type_str[17]; char battery_type_str[17];
snprintf(battery_type_str, 17, "%s battery", type_str); snprintf(battery_type_str, 17, "%s battery", type_str);
afs.gcs_terminate(true, battery_type_str); afs.gcs_terminate(true, battery_type_str);

View File

@ -47,7 +47,7 @@ void Plane::failsafe_check(void)
rc().read_input(); rc().read_input();
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (in_calibration) { if (in_calibration) {
// tell the failsafe system that we are calibrating // tell the failsafe system that we are calibrating
// sensors, so don't trigger failsafe // sensors, so don't trigger failsafe
@ -83,7 +83,7 @@ void Plane::failsafe_check(void)
// this is to allow the failsafe module to deliberately crash // this is to allow the failsafe module to deliberately crash
// the plane. Only used in extreme circumstances to meet the // the plane. Only used in extreme circumstances to meet the
// OBC rules // OBC rules
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (afs.should_crash_vehicle()) { if (afs.should_crash_vehicle()) {
afs.terminate_vehicle(); afs.terminate_vehicle();
if (!afs.terminating_vehicle_via_landing()) { if (!afs.terminating_vehicle_via_landing()) {

View File

@ -1756,7 +1756,7 @@ void QuadPlane::update(void)
ahrs_view->set_pitch_trim(_last_ahrs_trim_pitch); ahrs_view->set_pitch_trim(_last_ahrs_trim_pitch);
} }
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) { if (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) {
set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
motors->output(); motors->output();
@ -1983,7 +1983,7 @@ void QuadPlane::motors_output(bool run_rate_controller)
} }
} }
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (!hal.util->get_soft_armed() || if (!hal.util->get_soft_armed() ||
(plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) || (plane.afs.should_crash_vehicle() && !plane.afs.terminating_vehicle_via_landing()) ||
SRV_Channels::get_emergency_stop()) { SRV_Channels::get_emergency_stop()) {

View File

@ -723,7 +723,7 @@ void Plane::servos_twin_engine_mix(void)
float rud_gain = float(plane.g2.rudd_dt_gain) * 0.01f; float rud_gain = float(plane.g2.rudd_dt_gain) * 0.01f;
rudder_dt = rud_gain * SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / SERVO_MAX; rudder_dt = rud_gain * SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / SERVO_MAX;
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (afs.should_crash_vehicle()) { if (afs.should_crash_vehicle()) {
// when in AFS failsafe force rudder input for differential thrust to zero // when in AFS failsafe force rudder input for differential thrust to zero
rudder_dt = 0; rudder_dt = 0;
@ -824,7 +824,7 @@ void Plane::set_servos(void)
// this is to allow the failsafe module to deliberately crash // this is to allow the failsafe module to deliberately crash
// the plane. Only used in extreme circumstances to meet the // the plane. Only used in extreme circumstances to meet the
// OBC rules // OBC rules
#if ADVANCED_FAILSAFE == ENABLED #if AP_ADVANCEDFAILSAFE_ENABLED
if (afs.should_crash_vehicle()) { if (afs.should_crash_vehicle()) {
afs.terminate_vehicle(); afs.terminate_vehicle();
if (!afs.terminating_vehicle_via_landing()) { if (!afs.terminating_vehicle_via_landing()) {