AP_RPM: create singleton

This commit is contained in:
IamPete1 2019-02-25 16:48:19 +00:00 committed by Randy Mackay
parent b9cd3a8a39
commit 696953fb97
2 changed files with 13 additions and 0 deletions

View File

@ -92,6 +92,11 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
AP_RPM::AP_RPM(void) AP_RPM::AP_RPM(void)
{ {
AP_Param::setup_object_defaults(this, var_info); 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; return true;
} }
// singleton instance
AP_RPM *AP_RPM::_singleton;

View File

@ -92,7 +92,11 @@ public:
bool enabled(uint8_t instance) const; bool enabled(uint8_t instance) const;
static AP_RPM *get_singleton() { return _singleton; }
private: private:
static AP_RPM *_singleton;
RPM_State state[RPM_MAX_INSTANCES]; RPM_State state[RPM_MAX_INSTANCES];
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES]; AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
uint8_t num_instances:2; uint8_t num_instances:2;