diff --git a/libraries/AP_RPM/RPM_EFI.cpp b/libraries/AP_RPM/RPM_EFI.cpp
index 1cfa0ad011..82e126bf3c 100644
--- a/libraries/AP_RPM/RPM_EFI.cpp
+++ b/libraries/AP_RPM/RPM_EFI.cpp
@@ -13,19 +13,14 @@
along with this program. If not, see .
*/
-#include
-
-#include "RPM_EFI.h"
+#include "AP_RPM_config.h"
#if AP_RPM_EFI_ENABLED
+#include "RPM_EFI.h"
+#include
#include
-AP_RPM_EFI::AP_RPM_EFI(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
- AP_RPM_Backend(_ap_rpm, _instance, _state)
-{
-}
-
void AP_RPM_EFI::update(void)
{
AP_EFI *efi = AP::EFI();
diff --git a/libraries/AP_RPM/RPM_EFI.h b/libraries/AP_RPM/RPM_EFI.h
index 76710a3009..9d5ef49d25 100644
--- a/libraries/AP_RPM/RPM_EFI.h
+++ b/libraries/AP_RPM/RPM_EFI.h
@@ -14,7 +14,7 @@
*/
#pragma once
-#include "AP_RPM.h"
+#include "AP_RPM_config.h"
#if AP_RPM_EFI_ENABLED
@@ -23,13 +23,13 @@
class AP_RPM_EFI : public AP_RPM_Backend
{
public:
+
// constructor
- AP_RPM_EFI(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
+ using AP_RPM_Backend::AP_RPM_Backend;
// update state
void update(void) override;
-private:
};
#endif
diff --git a/libraries/AP_RPM/RPM_ESC_Telem.cpp b/libraries/AP_RPM/RPM_ESC_Telem.cpp
index abb9b5f78a..ea44ea29e9 100644
--- a/libraries/AP_RPM/RPM_ESC_Telem.cpp
+++ b/libraries/AP_RPM/RPM_ESC_Telem.cpp
@@ -13,23 +13,13 @@
along with this program. If not, see .
*/
-#include
-#include
-
-#include "RPM_ESC_Telem.h"
+#include "AP_RPM_config.h"
#if AP_RPM_ESC_TELEM_ENABLED
-extern const AP_HAL::HAL& hal;
-
-/*
- open the sensor in constructor
-*/
-AP_RPM_ESC_Telem::AP_RPM_ESC_Telem(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
- AP_RPM_Backend(_ap_rpm, _instance, _state)
-{
-}
-
+#include
+#include "RPM_ESC_Telem.h"
+#include
void AP_RPM_ESC_Telem::update(void)
{
diff --git a/libraries/AP_RPM/RPM_ESC_Telem.h b/libraries/AP_RPM/RPM_ESC_Telem.h
index e8ef243871..f9ebb632db 100644
--- a/libraries/AP_RPM/RPM_ESC_Telem.h
+++ b/libraries/AP_RPM/RPM_ESC_Telem.h
@@ -14,16 +14,17 @@
*/
#pragma once
-#include "AP_RPM.h"
-#include "RPM_Backend.h"
+#include "AP_RPM_config.h"
#if AP_RPM_ESC_TELEM_ENABLED
+#include "RPM_Backend.h"
+
class AP_RPM_ESC_Telem : public AP_RPM_Backend
{
public:
// constructor
- AP_RPM_ESC_Telem(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
+ using AP_RPM_Backend::AP_RPM_Backend;
// update state
void update(void) override;
diff --git a/libraries/AP_RPM/RPM_Generator.cpp b/libraries/AP_RPM/RPM_Generator.cpp
index 81b087f20f..0ed375d0cb 100644
--- a/libraries/AP_RPM/RPM_Generator.cpp
+++ b/libraries/AP_RPM/RPM_Generator.cpp
@@ -13,12 +13,12 @@
along with this program. If not, see .
*/
-#include
-
-#include "RPM_Generator.h"
+#include "AP_RPM_config.h"
#if AP_RPM_GENERATOR_ENABLED
-extern const AP_HAL::HAL& hal;
+
+#include "RPM_Generator.h"
+#include
void AP_RPM_Generator::update(void)
{
diff --git a/libraries/AP_RPM/RPM_Generator.h b/libraries/AP_RPM/RPM_Generator.h
index 627fc8ae9c..a9da14a121 100644
--- a/libraries/AP_RPM/RPM_Generator.h
+++ b/libraries/AP_RPM/RPM_Generator.h
@@ -14,12 +14,12 @@
*/
#pragma once
-#include "AP_RPM.h"
-#include "RPM_Backend.h"
-#include
+#include "AP_RPM_config.h"
#if AP_RPM_GENERATOR_ENABLED
+#include "RPM_Backend.h"
+
class AP_RPM_Generator : public AP_RPM_Backend
{
public:
diff --git a/libraries/AP_RPM/RPM_HarmonicNotch.cpp b/libraries/AP_RPM/RPM_HarmonicNotch.cpp
index e5dbbe766c..8fba549917 100644
--- a/libraries/AP_RPM/RPM_HarmonicNotch.cpp
+++ b/libraries/AP_RPM/RPM_HarmonicNotch.cpp
@@ -13,18 +13,15 @@
along with this program. If not, see .
*/
-#include "RPM_HarmonicNotch.h"
+#include "AP_RPM_config.h"
#if AP_RPM_HARMONICNOTCH_ENABLED
+#include "RPM_HarmonicNotch.h"
+
#include
#include
-AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
- AP_RPM_Backend(_ap_rpm, _instance, _state)
-{
-}
-
void AP_RPM_HarmonicNotch::update(void)
{
const AP_InertialSensor& ins = AP::ins();
diff --git a/libraries/AP_RPM/RPM_HarmonicNotch.h b/libraries/AP_RPM/RPM_HarmonicNotch.h
index 81d13a4cfa..5ea617f30d 100644
--- a/libraries/AP_RPM/RPM_HarmonicNotch.h
+++ b/libraries/AP_RPM/RPM_HarmonicNotch.h
@@ -14,16 +14,17 @@
*/
#pragma once
-#include "AP_RPM.h"
-#include "RPM_Backend.h"
+#include "AP_RPM_config.h"
#if AP_RPM_HARMONICNOTCH_ENABLED
+#include "RPM_Backend.h"
+
class AP_RPM_HarmonicNotch : public AP_RPM_Backend
{
public:
// constructor
- AP_RPM_HarmonicNotch(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
+ using AP_RPM_Backend::AP_RPM_Backend;
// update state
void update(void) override;
diff --git a/libraries/AP_RPM/RPM_Pin.cpp b/libraries/AP_RPM/RPM_Pin.cpp
index 8dc27fcac5..43d9443eb5 100644
--- a/libraries/AP_RPM/RPM_Pin.cpp
+++ b/libraries/AP_RPM/RPM_Pin.cpp
@@ -13,26 +13,20 @@
along with this program. If not, see .
*/
-#include "RPM_Pin.h"
+#include "AP_RPM_config.h"
#if AP_RPM_PIN_ENABLED
-#include
+#include "RPM_Pin.h"
+#include
#include
#include
+#include
extern const AP_HAL::HAL& hal;
AP_RPM_Pin::IrqState AP_RPM_Pin::irq_state[RPM_MAX_INSTANCES];
-/*
- open the sensor in constructor
-*/
-AP_RPM_Pin::AP_RPM_Pin(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) :
- AP_RPM_Backend(_ap_rpm, instance, _state)
-{
-}
-
/*
handle interrupt on an instance
*/
diff --git a/libraries/AP_RPM/RPM_Pin.h b/libraries/AP_RPM/RPM_Pin.h
index e196eddc21..95c957f1f5 100644
--- a/libraries/AP_RPM/RPM_Pin.h
+++ b/libraries/AP_RPM/RPM_Pin.h
@@ -14,20 +14,19 @@
*/
#pragma once
-#include "AP_RPM.h"
-
-#include "RPM_Backend.h"
+#include "AP_RPM_config.h"
#if AP_RPM_PIN_ENABLED
+#include "RPM_Backend.h"
+
#include
-#include
class AP_RPM_Pin : public AP_RPM_Backend
{
public:
- // constructor
- AP_RPM_Pin(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
+
+ using AP_RPM_Backend::AP_RPM_Backend;
// update state
void update(void) override;