AC_Avoid: add singleton
This commit is contained in:
parent
27a2b8a350
commit
413ef5a3b4
@ -57,6 +57,8 @@ AC_Avoid::AC_Avoid(const AP_AHRS& ahrs, const AC_Fence& fence, const AP_Proximit
|
||||
_proximity(proximity),
|
||||
_beacon(beacon)
|
||||
{
|
||||
_singleton = this;
|
||||
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
|
||||
@ -571,3 +573,15 @@ void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_ne
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
AC_Avoid *AC_Avoid::_singleton;
|
||||
|
||||
namespace AP {
|
||||
|
||||
AC_Avoid *ac_avoid()
|
||||
{
|
||||
return AC_Avoid::get_singleton();
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -34,6 +34,11 @@ public:
|
||||
AC_Avoid(const AC_Avoid &other) = delete;
|
||||
AC_Avoid &operator=(const AC_Avoid&) = delete;
|
||||
|
||||
// get singleton instance
|
||||
static AC_Avoid *get_singleton() {
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
/*
|
||||
* Adjusts the desired velocity so that the vehicle can stop
|
||||
* before the fence/object.
|
||||
@ -140,4 +145,10 @@ private:
|
||||
AP_Int8 _behavior; // avoidance behaviour (slide or stop)
|
||||
|
||||
bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable)
|
||||
|
||||
static AC_Avoid *_singleton;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AC_Avoid *ac_avoid();
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user