diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 48f0e68fc5..1ead3077cb 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -92,6 +92,11 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = { AP_RPM::AP_RPM(void) { AP_Param::setup_object_defaults(this, var_info); + + if (_singleton != nullptr) { + AP_HAL::panic("AP_RPM must be singleton"); + } + _singleton = this; } /* @@ -173,3 +178,7 @@ bool AP_RPM::enabled(uint8_t instance) const } return true; } + +// singleton instance +AP_RPM *AP_RPM::_singleton; + diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 3b3007588e..a473e63913 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -92,7 +92,11 @@ public: bool enabled(uint8_t instance) const; + static AP_RPM *get_singleton() { return _singleton; } + private: + static AP_RPM *_singleton; + RPM_State state[RPM_MAX_INSTANCES]; AP_RPM_Backend *drivers[RPM_MAX_INSTANCES]; uint8_t num_instances:2;