AP_AdvancedFailsafe: use mission singleton inside AP_AdvancedFailsafe
This commit is contained in:
parent
d0969a4476
commit
3013017369
@ -26,6 +26,7 @@
|
|||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
#include <AP_Mission/AP_Mission.h>
|
||||||
|
|
||||||
AP_AdvancedFailsafe *AP_AdvancedFailsafe::_singleton;
|
AP_AdvancedFailsafe *AP_AdvancedFailsafe::_singleton;
|
||||||
|
|
||||||
@ -208,6 +209,12 @@ AP_AdvancedFailsafe::check(bool geofence_breached, uint32_t last_valid_rc_ms)
|
|||||||
bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
|
bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
|
||||||
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
|
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
|
||||||
|
|
||||||
|
AP_Mission *_mission = AP::mission();
|
||||||
|
if (_mission == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
AP_Mission &mission = *_mission;
|
||||||
|
|
||||||
switch (_state) {
|
switch (_state) {
|
||||||
case STATE_PREFLIGHT:
|
case STATE_PREFLIGHT:
|
||||||
// we startup in preflight mode. This mode ends when
|
// we startup in preflight mode. This mode ends when
|
||||||
|
@ -22,9 +22,8 @@
|
|||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Mission/AP_Mission.h>
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
|
||||||
class AP_AdvancedFailsafe
|
class AP_AdvancedFailsafe
|
||||||
{
|
{
|
||||||
@ -52,8 +51,7 @@ public:
|
|||||||
AP_AdvancedFailsafe &operator=(const AP_AdvancedFailsafe&) = delete;
|
AP_AdvancedFailsafe &operator=(const AP_AdvancedFailsafe&) = delete;
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_AdvancedFailsafe(AP_Mission &_mission) :
|
AP_AdvancedFailsafe()
|
||||||
mission(_mission)
|
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
if (_singleton != nullptr) {
|
if (_singleton != nullptr) {
|
||||||
@ -106,8 +104,6 @@ protected:
|
|||||||
|
|
||||||
enum state _state;
|
enum state _state;
|
||||||
|
|
||||||
AP_Mission &mission;
|
|
||||||
|
|
||||||
AP_Int8 _enable;
|
AP_Int8 _enable;
|
||||||
// digital output pins for communicating with the failsafe board
|
// digital output pins for communicating with the failsafe board
|
||||||
AP_Int8 _heartbeat_pin;
|
AP_Int8 _heartbeat_pin;
|
||||||
|
Loading…
Reference in New Issue
Block a user