mirror of https://github.com/ArduPilot/ardupilot
Plane: changes for AP_AdvancedFailsafe naming
This commit is contained in:
parent
8163db1adb
commit
5d6dfd927b
|
@ -50,7 +50,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
SCHED_TASK(read_airspeed, 10, 100),
|
||||
SCHED_TASK(update_alt, 10, 200),
|
||||
SCHED_TASK(adjust_altitude_target, 10, 200),
|
||||
SCHED_TASK(obc_fs_check, 10, 100),
|
||||
SCHED_TASK(afs_fs_check, 10, 100),
|
||||
SCHED_TASK(gcs_update, 50, 500),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 500),
|
||||
SCHED_TASK(update_events, 50, 150),
|
||||
|
@ -286,14 +286,12 @@ void Plane::update_logging2(void)
|
|||
|
||||
|
||||
/*
|
||||
check for OBC failsafe check
|
||||
check for AFS failsafe check
|
||||
*/
|
||||
void Plane::obc_fs_check(void)
|
||||
void Plane::afs_fs_check(void)
|
||||
{
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// perform OBC failsafe checks
|
||||
obc.check(OBC_MODE(control_mode), failsafe.last_heartbeat_ms, geofence_breached(), failsafe.AFS_last_valid_rc_ms);
|
||||
#endif
|
||||
// perform AFS failsafe checks
|
||||
afs.check(AFS_MODE_PLANE(control_mode), failsafe.last_heartbeat_ms, geofence_breached(), failsafe.AFS_last_valid_rc_ms);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -1219,12 +1219,10 @@ void Plane::set_servos(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the plane. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
obc.check_crash_plane();
|
||||
#endif
|
||||
afs.check_crash_plane();
|
||||
|
||||
#if HIL_SUPPORT
|
||||
if (g.hil_mode == 1) {
|
||||
|
|
|
@ -1315,11 +1315,9 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
GOBJECT(sitl, "SIM_", SITL::SITL),
|
||||
#endif
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// @Group: AFS_
|
||||
// @Path: ../libraries/APM_OBC/APM_OBC.cpp
|
||||
GOBJECT(obc, "AFS_", APM_OBC),
|
||||
#endif
|
||||
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
|
||||
GOBJECT(afs, "AFS_", AP_AdvancedFailsafe),
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
// @Group: FLOW
|
||||
|
|
|
@ -321,7 +321,7 @@ public:
|
|||
|
||||
// other objects
|
||||
k_param_sitl = 230,
|
||||
k_param_obc,
|
||||
k_param_afs,
|
||||
k_param_rollController,
|
||||
k_param_pitchController,
|
||||
k_param_yawController,
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
|
||||
#include <APM_OBC/APM_OBC.h>
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
#include <APM_Control/APM_Control.h>
|
||||
#include <APM_Control/AP_AutoTune.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
|
@ -632,9 +632,7 @@ private:
|
|||
AP_ADSB adsb {ahrs};
|
||||
|
||||
// Outback Challenge Failsafe Support
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
APM_OBC obc {mission, barometer, gps, rcmap};
|
||||
#endif
|
||||
AP_AdvancedFailsafe afs {mission, barometer, gps, rcmap};
|
||||
|
||||
/*
|
||||
meta data to support counting the number of circles in a loiter
|
||||
|
@ -991,7 +989,7 @@ private:
|
|||
void update_GPS_10Hz(void);
|
||||
void update_compass(void);
|
||||
void update_alt(void);
|
||||
void obc_fs_check(void);
|
||||
void afs_fs_check(void);
|
||||
void compass_accumulate(void);
|
||||
void compass_cal_update();
|
||||
void barometer_accumulate(void);
|
||||
|
|
|
@ -405,11 +405,6 @@
|
|||
# define RESET_SWITCH_CHAN_PWM 1750
|
||||
#endif
|
||||
|
||||
// OBC Failsafe enable
|
||||
#ifndef OBC_FAILSAFE
|
||||
#define OBC_FAILSAFE ENABLED
|
||||
#endif
|
||||
|
||||
#define HIL_SUPPORT ENABLED
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -42,13 +42,11 @@ void Plane::failsafe_check(void)
|
|||
if (in_failsafe && tnow - last_timestamp > 20000) {
|
||||
last_timestamp = tnow;
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
if (in_calibration) {
|
||||
// tell the failsafe system that we are calibrating
|
||||
// sensors, so don't trigger failsafe
|
||||
obc.heartbeat();
|
||||
afs.heartbeat();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (hal.rcin->num_channels() < 5) {
|
||||
// we don't have any RC input to pass through
|
||||
|
@ -81,12 +79,10 @@ void Plane::failsafe_check(void)
|
|||
channel_output_mixer(g.elevon_output, channel_pitch, channel_roll);
|
||||
}
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the plane. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
obc.check_crash_plane();
|
||||
#endif
|
||||
afs.check_crash_plane();
|
||||
|
||||
if (!demoing_servos) {
|
||||
channel_roll->output();
|
||||
|
|
|
@ -18,7 +18,7 @@ LIBRARIES += AP_Relay
|
|||
LIBRARIES += AP_Camera
|
||||
LIBRARIES += AP_Airspeed
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += APM_OBC
|
||||
LIBRARIES += AP_AdvancedFailsafe
|
||||
LIBRARIES += APM_Control
|
||||
LIBRARIES += AP_AutoTune
|
||||
LIBRARIES += GCS
|
||||
|
|
|
@ -8,7 +8,7 @@ def build(bld):
|
|||
ap_vehicle=vehicle,
|
||||
ap_libraries=bld.ap_common_vehicle_libraries() + [
|
||||
'APM_Control',
|
||||
'APM_OBC',
|
||||
'AP_AdvancedFailsafe',
|
||||
'AP_ADSB',
|
||||
'AP_Arming',
|
||||
'AP_Camera',
|
||||
|
|
Loading…
Reference in New Issue