mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AdvancedFailSafe: add singleton getter
This commit is contained in:
parent
a761cb62de
commit
9f8553d422
@ -27,6 +27,8 @@
|
|||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
|
||||||
|
AP_AdvancedFailsafe *AP_AdvancedFailsafe::_singleton;
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
@ -453,3 +455,12 @@ void AP_AdvancedFailsafe::max_range_update(void)
|
|||||||
_terminate.set_and_notify(1);
|
_terminate.set_and_notify(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
|
||||||
|
AP_AdvancedFailsafe *advancedfailsafe()
|
||||||
|
{
|
||||||
|
return AP_AdvancedFailsafe::get_singleton();
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
@ -48,18 +48,31 @@ public:
|
|||||||
TERMINATE_ACTION_LAND = 43
|
TERMINATE_ACTION_LAND = 43
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_AdvancedFailsafe(const AP_AdvancedFailsafe &other) = delete;
|
||||||
|
AP_AdvancedFailsafe &operator=(const AP_AdvancedFailsafe&) = delete;
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_AdvancedFailsafe(AP_Mission &_mission) :
|
AP_AdvancedFailsafe(AP_Mission &_mission) :
|
||||||
mission(_mission)
|
mission(_mission)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
if (_singleton != nullptr) {
|
||||||
|
AP_HAL::panic("AP_Logger must be singleton");
|
||||||
|
}
|
||||||
|
|
||||||
|
_singleton = this;
|
||||||
_state = STATE_PREFLIGHT;
|
_state = STATE_PREFLIGHT;
|
||||||
_terminate.set(0);
|
_terminate.set(0);
|
||||||
|
|
||||||
_saved_wp = 0;
|
_saved_wp = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get singleton instance
|
||||||
|
static AP_AdvancedFailsafe *get_singleton(void) {
|
||||||
|
return _singleton;
|
||||||
|
}
|
||||||
|
|
||||||
bool enabled() { return _enable; }
|
bool enabled() { return _enable; }
|
||||||
|
|
||||||
// check that everything is OK
|
// check that everything is OK
|
||||||
@ -147,6 +160,12 @@ protected:
|
|||||||
bool check_altlimit(void);
|
bool check_altlimit(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
static AP_AdvancedFailsafe *_singleton;
|
||||||
|
|
||||||
// update maximum range check
|
// update maximum range check
|
||||||
void max_range_update();
|
void max_range_update();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
AP_AdvancedFailsafe *advancedfailsafe();
|
||||||
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user