mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: add and use AP_RPM_ENABLED
... and backend-specific equivalents
This commit is contained in:
parent
d21aa2a1ed
commit
63c551ce13
|
@ -14,6 +14,9 @@
|
|||
*/
|
||||
|
||||
#include "AP_RPM.h"
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
|
||||
#include "RPM_Pin.h"
|
||||
#include "RPM_SITL.h"
|
||||
#include "RPM_EFI.h"
|
||||
|
@ -66,36 +69,40 @@ void AP_RPM::init(void)
|
|||
|
||||
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
||||
switch (_params[i].type) {
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
#if AP_RPM_PIN_ENABLED
|
||||
case RPM_TYPE_PWM:
|
||||
case RPM_TYPE_PIN:
|
||||
// PWM option same as PIN option, for upgrade
|
||||
drivers[i] = new AP_RPM_Pin(*this, i, state[i]);
|
||||
break;
|
||||
#endif
|
||||
#endif // AP_RPM_PIN_ENABLED
|
||||
#if AP_RPM_ESC_TELEM_ENABLED
|
||||
case RPM_TYPE_ESC_TELEM:
|
||||
drivers[i] = new AP_RPM_ESC_Telem(*this, i, state[i]);
|
||||
break;
|
||||
#if HAL_EFI_ENABLED
|
||||
#endif // AP_RPM_ESC_TELEM_ENABLED
|
||||
#if AP_RPM_EFI_ENABLED
|
||||
case RPM_TYPE_EFI:
|
||||
drivers[i] = new AP_RPM_EFI(*this, i, state[i]);
|
||||
break;
|
||||
#endif
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#endif // AP_RPM_EFI_ENABLED
|
||||
#if AP_RPM_GENERATOR_ENABLED
|
||||
case RPM_TYPE_GENERATOR:
|
||||
drivers[i] = new AP_RPM_Generator(*this, i, state[i]);
|
||||
break;
|
||||
#endif
|
||||
#endif // AP_RPM_GENERATOR_ENABLED
|
||||
#if AP_RPM_HARMONICNOTCH_ENABLED
|
||||
// include harmonic notch last
|
||||
// this makes whatever process is driving the dynamic notch appear as an RPM value
|
||||
case RPM_TYPE_HNTCH:
|
||||
drivers[i] = new AP_RPM_HarmonicNotch(*this, i, state[i]);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif // AP_RPM_HARMONICNOTCH_ENABLED
|
||||
#if AP_RPM_SIM_ENABLED
|
||||
case RPM_TYPE_SITL:
|
||||
drivers[i] = new AP_RPM_SITL(*this, i, state[i]);
|
||||
break;
|
||||
#endif
|
||||
#endif // AP_RPM_SIM_ENABLED
|
||||
}
|
||||
if (drivers[i] != nullptr) {
|
||||
// we loaded a driver for this instance, so it must be
|
||||
|
@ -301,3 +308,5 @@ AP_RPM *rpm()
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_RPM_ENABLED
|
||||
|
|
|
@ -14,6 +14,10 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_RPM_config.h"
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
@ -37,13 +41,23 @@ public:
|
|||
// RPM driver types
|
||||
enum RPM_Type {
|
||||
RPM_TYPE_NONE = 0,
|
||||
#if AP_RPM_PIN_ENABLED
|
||||
RPM_TYPE_PWM = 1,
|
||||
RPM_TYPE_PIN = 2,
|
||||
#endif
|
||||
#if AP_RPM_EFI_ENABLED
|
||||
RPM_TYPE_EFI = 3,
|
||||
#endif
|
||||
#if AP_RPM_HARMONICNOTCH_ENABLED
|
||||
RPM_TYPE_HNTCH = 4,
|
||||
#endif
|
||||
#if AP_RPM_ESC_TELEM_ENABLED
|
||||
RPM_TYPE_ESC_TELEM = 5,
|
||||
#endif
|
||||
#if AP_RPM_GENERATOR_ENABLED
|
||||
RPM_TYPE_GENERATOR = 6,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#endif
|
||||
#if AP_RPM_SIM_ENABLED
|
||||
RPM_TYPE_SITL = 10,
|
||||
#endif
|
||||
};
|
||||
|
@ -110,3 +124,5 @@ private:
|
|||
namespace AP {
|
||||
AP_RPM *rpm();
|
||||
};
|
||||
|
||||
#endif // AP_RPM_ENABLED
|
||||
|
|
|
@ -0,0 +1,38 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#include <AP_EFI/AP_EFI_config.h>
|
||||
#include <AP_Generator/AP_Generator.h>
|
||||
|
||||
#ifndef AP_RPM_ENABLED
|
||||
#define AP_RPM_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_RPM_BACKEND_DEFAULT_ENABLED AP_RPM_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_EFI_ENABLED
|
||||
#define AP_RPM_EFI_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_EFI_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_ESC_TELEM_ENABLED
|
||||
#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_HARMONICNOTCH_ENABLED
|
||||
#define AP_RPM_HARMONICNOTCH_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_PIN_ENABLED
|
||||
#define AP_RPM_PIN_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_SIM_ENABLED
|
||||
#define AP_RPM_SIM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RPM_GENERATOR_ENABLED
|
||||
#define AP_RPM_GENERATOR_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_GENERATOR_ENABLED
|
||||
#endif
|
|
@ -13,10 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_RPM.h"
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
/*
|
||||
base class constructor.
|
||||
|
@ -27,3 +30,5 @@ AP_RPM_Backend::AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_St
|
|||
{
|
||||
state.instance = instance;
|
||||
}
|
||||
|
||||
#endif // AP_RPM_ENABLED
|
||||
|
|
|
@ -16,6 +16,8 @@
|
|||
|
||||
#include "AP_RPM.h"
|
||||
|
||||
#if AP_RPM_ENABLED
|
||||
|
||||
class AP_RPM_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -41,3 +43,5 @@ protected:
|
|||
AP_RPM &ap_rpm;
|
||||
AP_RPM::RPM_State &state;
|
||||
};
|
||||
|
||||
#endif // AP_RPM_ENABLED
|
||||
|
|
|
@ -17,12 +17,10 @@
|
|||
|
||||
#include "RPM_EFI.h"
|
||||
|
||||
#if HAL_EFI_ENABLED
|
||||
extern const AP_HAL::HAL& hal;
|
||||
#if AP_RPM_EFI_ENABLED
|
||||
|
||||
#include <AP_EFI/AP_EFI.h>
|
||||
|
||||
/*
|
||||
open the sensor in constructor
|
||||
*/
|
||||
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)
|
||||
{
|
||||
|
@ -41,4 +39,4 @@ void AP_RPM_EFI::update(void)
|
|||
state.last_reading_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
#endif // HAL_EFI_ENABLED
|
||||
#endif // AP_RPM_EFI_ENABLED
|
||||
|
|
|
@ -15,8 +15,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RPM.h"
|
||||
|
||||
#if AP_RPM_EFI_ENABLED
|
||||
|
||||
#include "RPM_Backend.h"
|
||||
#include <AP_EFI/AP_EFI.h>
|
||||
|
||||
class AP_RPM_EFI : public AP_RPM_Backend
|
||||
{
|
||||
|
@ -30,3 +32,5 @@ public:
|
|||
private:
|
||||
uint8_t instance;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -18,6 +18,8 @@
|
|||
|
||||
#include "RPM_ESC_Telem.h"
|
||||
|
||||
#if AP_RPM_ESC_TELEM_ENABLED
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
|
@ -40,3 +42,5 @@ void AP_RPM_ESC_Telem::update(void)
|
|||
state.last_reading_ms = AP_HAL::millis();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // AP_RPM_ESC_TELEM_ENABLED
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
#include "AP_RPM.h"
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
#if AP_RPM_ESC_TELEM_ENABLED
|
||||
|
||||
class AP_RPM_ESC_Telem : public AP_RPM_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -28,3 +30,5 @@ public:
|
|||
private:
|
||||
uint8_t instance;
|
||||
};
|
||||
|
||||
#endif // AP_RPM_ESC_TELEM_ENABLED
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#include "RPM_Generator.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_RPM_GENERATOR_ENABLED
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void AP_RPM_Generator::update(void)
|
||||
|
@ -35,4 +35,4 @@ void AP_RPM_Generator::update(void)
|
|||
}
|
||||
}
|
||||
|
||||
#endif // HAL_GENERATOR_ENABLED
|
||||
#endif // AP_RPM_GENERATOR_ENABLED
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#include "RPM_Backend.h"
|
||||
#include <AP_Generator/AP_Generator.h>
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_RPM_GENERATOR_ENABLED
|
||||
|
||||
class AP_RPM_Generator : public AP_RPM_Backend
|
||||
{
|
||||
|
@ -30,5 +30,4 @@ public:
|
|||
void update(void) override;
|
||||
};
|
||||
|
||||
#endif // HAL_GENERATOR_ENABLED
|
||||
|
||||
#endif // AP_RPM_GENERATOR_ENABLED
|
||||
|
|
|
@ -13,16 +13,13 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "RPM_HarmonicNotch.h"
|
||||
|
||||
#if AP_RPM_HARMONICNOTCH_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
|
||||
#include "RPM_HarmonicNotch.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
open the sensor in constructor
|
||||
*/
|
||||
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)
|
||||
{
|
||||
|
@ -31,8 +28,8 @@ AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, A
|
|||
|
||||
void AP_RPM_HarmonicNotch::update(void)
|
||||
{
|
||||
AP_InertialSensor& ins = AP::ins();
|
||||
for (auto ¬ch : ins.harmonic_notches) {
|
||||
const AP_InertialSensor& ins = AP::ins();
|
||||
for (const auto ¬ch : ins.harmonic_notches) {
|
||||
if (notch.params.enabled() &&
|
||||
notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) {
|
||||
state.rate_rpm = notch.calculated_notch_freq_hz[0] * 60;
|
||||
|
@ -43,3 +40,4 @@ void AP_RPM_HarmonicNotch::update(void)
|
|||
}
|
||||
}
|
||||
|
||||
#endif // AP_RPM_HARMONICNOTCH_ENABLED
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
#include "AP_RPM.h"
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
#if AP_RPM_HARMONICNOTCH_ENABLED
|
||||
|
||||
class AP_RPM_HarmonicNotch : public AP_RPM_Backend
|
||||
{
|
||||
public:
|
||||
|
@ -29,3 +31,5 @@ public:
|
|||
private:
|
||||
uint8_t instance;
|
||||
};
|
||||
|
||||
#endif // AP_RPM_HARMONICNOTCH_ENABLED
|
||||
|
|
|
@ -13,9 +13,12 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "RPM_Pin.h"
|
||||
|
||||
#if AP_RPM_PIN_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include <AP_HAL/GPIO.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
|
@ -111,3 +114,5 @@ void AP_RPM_Pin::update(void)
|
|||
state.rate_rpm = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_RPM_PIN_ENABLED
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
#include "AP_RPM.h"
|
||||
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
#if AP_RPM_PIN_ENABLED
|
||||
|
||||
#include <Filter/Filter.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
|
@ -46,3 +49,5 @@ private:
|
|||
uint32_t timestamp);
|
||||
|
||||
};
|
||||
|
||||
#endif // AP_RPM_PIN_ENABLED
|
||||
|
|
Loading…
Reference in New Issue