mirror of https://github.com/ArduPilot/ardupilot
Copter: rename ADVANCED_FAILSAFE to AP_COPTER_ADVANCED_FAILSAFE_ENABLED
to make integration with custom build server work
This commit is contained in:
parent
6acbfde357
commit
bb12b988f7
|
@ -27,7 +27,7 @@
|
|||
// features below are disabled by default on all boards
|
||||
//#define CAL_ALWAYS_REBOOT // flight controller will reboot after compass or accelerometer calibration completes
|
||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||
//#define ADVANCED_FAILSAFE 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
|
||||
//#define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 1 // enabled advanced failsafe which allows running a portion of the mission in failsafe events
|
||||
|
||||
// other settings
|
||||
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
|
||||
|
|
|
@ -232,7 +232,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
#if HAL_ADSB_ENABLED
|
||||
SCHED_TASK(avoidance_adsb_update, 10, 100, 138),
|
||||
#endif
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
SCHED_TASK(afs_fs_check, 10, 100, 141),
|
||||
#endif
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
|
|
|
@ -137,7 +137,7 @@
|
|||
#include <AP_OSD/AP_OSD.h>
|
||||
#endif
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
# include "afs_copter.h"
|
||||
#endif
|
||||
#if TOY_MODE_ENABLED
|
||||
|
@ -183,7 +183,7 @@ public:
|
|||
friend class ParametersG2;
|
||||
friend class AP_Avoidance_Copter;
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
friend class AP_AdvancedFailsafe_Copter;
|
||||
#endif
|
||||
friend class AP_Arming_Copter;
|
||||
|
@ -802,7 +802,7 @@ private:
|
|||
// failsafe.cpp
|
||||
void failsafe_enable();
|
||||
void failsafe_disable();
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
void afs_fs_check(void);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -1519,7 +1519,7 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
|
|||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) {
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
|
|
@ -771,7 +771,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1),
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// @Group: AFS_
|
||||
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
|
||||
AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe),
|
||||
|
@ -1251,7 +1251,7 @@ ParametersG2::ParametersG2(void)
|
|||
#if HAL_PROXIMITY_ENABLED
|
||||
, proximity()
|
||||
#endif
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
,afs()
|
||||
#endif
|
||||
#if MODE_SMARTRTL_ENABLED
|
||||
|
|
|
@ -531,7 +531,7 @@ public:
|
|||
// whether to enforce acceptance of packets only from sysid_my_gcs
|
||||
AP_Int8 sysid_enforce;
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// advanced failsafe library
|
||||
AP_AdvancedFailsafe_Copter afs;
|
||||
#endif
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
#include "Copter.h"
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
|
||||
/*
|
||||
setup radio_out values for all channels to termination values
|
||||
|
@ -63,4 +63,4 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void)
|
|||
{
|
||||
copter.set_mode(Mode::Number::AUTO,ModeReason::GCS_FAILSAFE);
|
||||
}
|
||||
#endif // ADVANCED_FAILSAFE
|
||||
#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
|
|
|
@ -18,7 +18,9 @@
|
|||
advanced failsafe support for copter
|
||||
*/
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#include "config.h"
|
||||
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
|
||||
/*
|
||||
|
@ -44,5 +46,5 @@ protected:
|
|||
void set_mode_auto(void) override;
|
||||
};
|
||||
|
||||
#endif // ADVANCED_FAILSAFE
|
||||
#endif // AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
|
||||
|
|
|
@ -574,8 +574,8 @@
|
|||
// Developer Items
|
||||
//
|
||||
|
||||
#ifndef ADVANCED_FAILSAFE
|
||||
# define ADVANCED_FAILSAFE 0
|
||||
#ifndef AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
# define AP_COPTER_ADVANCED_FAILSAFE_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef CH_MODE_DEFAULT
|
||||
|
|
|
@ -492,7 +492,7 @@ void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){
|
|||
set_mode_SmartRTL_or_land_with_pause(reason);
|
||||
break;
|
||||
case FailsafeAction::TERMINATE: {
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
g2.afs.gcs_terminate(true, "Failsafe");
|
||||
#else
|
||||
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);
|
||||
|
|
|
@ -72,7 +72,7 @@ void Copter::failsafe_check()
|
|||
}
|
||||
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
/*
|
||||
check for AFS failsafe check
|
||||
*/
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#include <AP_Math/chirp.h>
|
||||
#include <AP_ExternalControl/AP_ExternalControl_config.h> // TODO why is this needed if Copter.h includes this
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
#include "afs_copter.h"
|
||||
#endif
|
||||
|
||||
|
@ -134,7 +134,7 @@ public:
|
|||
virtual bool allows_flip() const { return false; }
|
||||
virtual bool crash_check_enabled() const { return true; }
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// Return the type of this mode for use by advanced failsafe
|
||||
virtual AP_AdvancedFailsafe_Copter::control_mode afs_mode() const { return AP_AdvancedFailsafe_Copter::control_mode::AFS_STABILIZED; }
|
||||
#endif
|
||||
|
@ -517,7 +517,7 @@ public:
|
|||
bool allows_inverted() const override { return true; };
|
||||
#endif
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// Return the type of this mode for use by advanced failsafe
|
||||
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
|
||||
#endif
|
||||
|
@ -1068,7 +1068,7 @@ public:
|
|||
|
||||
bool requires_terrain_failsafe() const override { return true; }
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// Return the type of this mode for use by advanced failsafe
|
||||
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
|
||||
#endif
|
||||
|
@ -1243,7 +1243,7 @@ public:
|
|||
|
||||
bool is_landing() const override { return true; };
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// Return the type of this mode for use by advanced failsafe
|
||||
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
|
||||
#endif
|
||||
|
@ -1425,7 +1425,7 @@ public:
|
|||
|
||||
bool requires_terrain_failsafe() const override { return true; }
|
||||
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// Return the type of this mode for use by advanced failsafe
|
||||
AP_AdvancedFailsafe_Copter::control_mode afs_mode() const override { return AP_AdvancedFailsafe_Copter::control_mode::AFS_AUTO; }
|
||||
#endif
|
||||
|
|
|
@ -135,7 +135,7 @@ void Copter::auto_disarm_check()
|
|||
// motors_output - send output to motors library which will adjust and send to ESCs and servos
|
||||
void Copter::motors_output()
|
||||
{
|
||||
#if ADVANCED_FAILSAFE
|
||||
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the vehicle. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
|
|
Loading…
Reference in New Issue