Browse Source

AP_RPM: create singleton

mission-4.1.18
IamPete1 6 years ago committed by Randy Mackay
parent
commit
696953fb97
  1. 9
      libraries/AP_RPM/AP_RPM.cpp
  2. 4
      libraries/AP_RPM/AP_RPM.h

9
libraries/AP_RPM/AP_RPM.cpp

@ -92,6 +92,11 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = { @@ -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 @@ -173,3 +178,7 @@ bool AP_RPM::enabled(uint8_t instance) const
}
return true;
}
// singleton instance
AP_RPM *AP_RPM::_singleton;

4
libraries/AP_RPM/AP_RPM.h

@ -92,7 +92,11 @@ public: @@ -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;

Loading…
Cancel
Save