AP_RPM: tidy constructors and use of config.h

This commit is contained in:
Peter Barker 2023-08-13 15:29:07 +10:00 committed by Peter Barker
parent 8df2d4998b
commit 5a0f0915ed
10 changed files with 37 additions and 60 deletions

View File

@ -13,19 +13,14 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "RPM_EFI.h"
#include "AP_RPM_config.h"
#if AP_RPM_EFI_ENABLED
#include "RPM_EFI.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_EFI/AP_EFI.h>
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();

View File

@ -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

View File

@ -13,23 +13,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#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 <AP_ESC_Telem/AP_ESC_Telem.h>
#include "RPM_ESC_Telem.h"
#include <AP_HAL/AP_HAL.h>
void AP_RPM_ESC_Telem::update(void)
{

View File

@ -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;

View File

@ -13,12 +13,12 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#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 <AP_Generator/AP_Generator.h>
void AP_RPM_Generator::update(void)
{

View File

@ -14,12 +14,12 @@
*/
#pragma once
#include "AP_RPM.h"
#include "RPM_Backend.h"
#include <AP_Generator/AP_Generator.h>
#include "AP_RPM_config.h"
#if AP_RPM_GENERATOR_ENABLED
#include "RPM_Backend.h"
class AP_RPM_Generator : public AP_RPM_Backend
{
public:

View File

@ -13,18 +13,15 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "RPM_HarmonicNotch.h"
#include "AP_RPM_config.h"
#if AP_RPM_HARMONICNOTCH_ENABLED
#include "RPM_HarmonicNotch.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
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();

View File

@ -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;

View File

@ -13,26 +13,20 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "RPM_Pin.h"
#include "AP_RPM_config.h"
#if AP_RPM_PIN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "RPM_Pin.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/GPIO.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Math/AP_Math.h>
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
*/

View File

@ -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 <Filter/Filter.h>
#include <AP_Math/AP_Math.h>
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;