diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 07b6e7b7c5..3b3007588e 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -29,9 +29,7 @@ class AP_RPM friend class AP_RPM_Backend; public: - static AP_RPM create() { return AP_RPM{}; } - - constexpr AP_RPM(AP_RPM &&other) = default; + AP_RPM(); /* Do not allow copies */ AP_RPM(const AP_RPM &other) = delete; @@ -95,8 +93,6 @@ public: bool enabled(uint8_t instance) const; private: - AP_RPM(); - RPM_State state[RPM_MAX_INSTANCES]; AP_RPM_Backend *drivers[RPM_MAX_INSTANCES]; uint8_t num_instances:2; diff --git a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp index 9d84d7e242..283ad99687 100644 --- a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp +++ b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp @@ -26,7 +26,7 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -static AP_RPM RPM = AP_RPM::create(); +static AP_RPM RPM; char sensor_state;