mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Compass: add AP::compass() singleton getter
This commit is contained in:
parent
631e967df3
commit
a3a1967e05
@ -462,6 +462,13 @@ Compass::Compass(void) :
|
|||||||
_null_init_done(false),
|
_null_init_done(false),
|
||||||
_hil_mode(false)
|
_hil_mode(false)
|
||||||
{
|
{
|
||||||
|
if (_singleton != nullptr) {
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
AP_HAL::panic("Compass must be singleton");
|
||||||
|
#endif
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
_singleton = this;
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
|
for (uint8_t i=0; i<COMPASS_MAX_BACKEND; i++) {
|
||||||
_backends[i] = nullptr;
|
_backends[i] = nullptr;
|
||||||
@ -1324,3 +1331,15 @@ bool Compass::consistent() const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// singleton instance
|
||||||
|
Compass *Compass::_singleton;
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
|
||||||
|
Compass &compass()
|
||||||
|
{
|
||||||
|
return *Compass::get_singleton();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
@ -56,6 +56,11 @@ public:
|
|||||||
Compass(const Compass &other) = delete;
|
Compass(const Compass &other) = delete;
|
||||||
Compass &operator=(const Compass&) = delete;
|
Compass &operator=(const Compass&) = delete;
|
||||||
|
|
||||||
|
// get singleton instance
|
||||||
|
static Compass *get_singleton() {
|
||||||
|
return _singleton;
|
||||||
|
}
|
||||||
|
|
||||||
friend class CompassLearn;
|
friend class CompassLearn;
|
||||||
|
|
||||||
/// Initialize the compass device.
|
/// Initialize the compass device.
|
||||||
@ -326,6 +331,7 @@ public:
|
|||||||
uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }
|
uint8_t get_filter_range() const { return uint8_t(_filter_range.get()); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
static Compass *_singleton;
|
||||||
/// Register a new compas driver, allocating an instance number
|
/// Register a new compas driver, allocating an instance number
|
||||||
///
|
///
|
||||||
/// @return number of compass instances
|
/// @return number of compass instances
|
||||||
@ -466,3 +472,7 @@ private:
|
|||||||
|
|
||||||
AP_Int8 _filter_range;
|
AP_Int8 _filter_range;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
Compass &compass();
|
||||||
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user