mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Generator: add defines for generator backends
This commit is contained in:
parent
9836b7c549
commit
b070217308
@ -65,19 +65,23 @@ void AP_Generator::init()
|
||||
// Not using a generator
|
||||
return;
|
||||
|
||||
#if AP_GENERATOR_IE650_800_ENABLED
|
||||
case Type::IE_650_800:
|
||||
_driver_ptr = new AP_Generator_IE_650_800(*this);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AP_GENERATOR_IE2400_ENABLED
|
||||
case Type::IE_2400:
|
||||
_driver_ptr = new AP_Generator_IE_2400(*this);
|
||||
break;
|
||||
|
||||
case Type::RICHENPOWER:
|
||||
#if AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
_driver_ptr = new AP_Generator_RichenPower(*this);
|
||||
#endif
|
||||
|
||||
#if AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
case Type::RICHENPOWER:
|
||||
_driver_ptr = new AP_Generator_RichenPower(*this);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (_driver_ptr != nullptr) {
|
||||
|
@ -81,9 +81,15 @@ private:
|
||||
|
||||
enum class Type {
|
||||
GEN_DISABLED = 0,
|
||||
#if AP_GENERATOR_IE650_800_ENABLED
|
||||
IE_650_800 = 1,
|
||||
#endif
|
||||
#if AP_GENERATOR_IE2400_ENABLED
|
||||
IE_2400 = 2,
|
||||
#endif
|
||||
#if AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
RICHENPOWER = 3,
|
||||
#endif
|
||||
// LOWEHEISER = 4,
|
||||
};
|
||||
|
||||
|
@ -15,7 +15,7 @@
|
||||
|
||||
#include "AP_Generator_IE_2400.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE2400_ENABLED
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
@ -203,4 +203,4 @@ void AP_Generator_IE_2400::log_write()
|
||||
_err_code
|
||||
);
|
||||
}
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE2400_ENABLED
|
||||
|
@ -2,7 +2,7 @@
|
||||
|
||||
#include "AP_Generator_IE_FuelCell.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE2400_ENABLED
|
||||
|
||||
class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell
|
||||
{
|
||||
@ -53,4 +53,5 @@ private:
|
||||
uint16_t _spm_pwr; // Stack Power Module (SPM) power draw (Watts)
|
||||
|
||||
};
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE2400_ENABLED
|
||||
|
||||
|
@ -15,7 +15,7 @@
|
||||
|
||||
#include "AP_Generator_IE_650_800.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE650_800_ENABLED
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -122,4 +122,5 @@ AP_BattMonitor::Failsafe AP_Generator_IE_650_800::update_failsafes() const
|
||||
return AP_BattMonitor::Failsafe::None;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE650_800_ENABLED
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
|
||||
#include "AP_Generator_IE_FuelCell.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE650_800_ENABLED
|
||||
|
||||
class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell
|
||||
{
|
||||
@ -95,4 +95,4 @@ private:
|
||||
| ERROR_BAT_UT; // (0x8), Battery undertemperature (<-15 degC)
|
||||
|
||||
};
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE650_800_ENABLED
|
||||
|
@ -15,7 +15,7 @@
|
||||
|
||||
#include "AP_Generator_IE_FuelCell.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE_ENABLED
|
||||
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
@ -190,4 +190,4 @@ bool AP_Generator_IE_FuelCell::check_for_err_code_if_changed(char* msg_txt, uint
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE_ENABLED
|
||||
|
@ -2,7 +2,7 @@
|
||||
|
||||
#include "AP_Generator_Backend.h"
|
||||
|
||||
#if HAL_GENERATOR_ENABLED
|
||||
#if AP_GENERATOR_IE_ENABLED
|
||||
|
||||
class AP_Generator_IE_FuelCell : public AP_Generator_Backend
|
||||
{
|
||||
@ -100,4 +100,4 @@ protected:
|
||||
bool check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len);
|
||||
|
||||
};
|
||||
#endif
|
||||
#endif // AP_GENERATOR_IE_ENABLED
|
||||
|
@ -3,10 +3,6 @@
|
||||
|
||||
#include "AP_Generator_Backend.h"
|
||||
|
||||
#ifndef AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
#define AP_GENERATOR_RICHENPOWER_ENABLED 0
|
||||
#endif
|
||||
|
||||
#if AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
@ -5,3 +5,23 @@
|
||||
#ifndef HAL_GENERATOR_ENABLED
|
||||
#define HAL_GENERATOR_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_GENERATOR_BACKEND_DEFAULT_ENABLED HAL_GENERATOR_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_IE_ENABLED
|
||||
#define AP_GENERATOR_IE_ENABLED AP_GENERATOR_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_IE2400_ENABLED
|
||||
#define AP_GENERATOR_IE2400_ENABLED AP_GENERATOR_IE_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_IE650_800_ENABLED
|
||||
#define AP_GENERATOR_IE650_800_ENABLED AP_GENERATOR_IE_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_GENERATOR_RICHENPOWER_ENABLED
|
||||
#define AP_GENERATOR_RICHENPOWER_ENABLED 0
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user