AP_BattMonitor: add defines for all battery backends

This commit is contained in:
Peter Barker 2023-03-07 13:02:49 +11:00 committed by Peter Barker
parent ff0c4133c6
commit 85501f8219
43 changed files with 333 additions and 108 deletions

View File

@ -266,64 +266,74 @@ AP_BattMonitor::init()
case Type::ANALOG_VOLTAGE_AND_CURRENT:
drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]);
break;
#if AP_BATTMON_SMBUS_SOLO_ENABLED
#if AP_BATTERY_SMBUS_SOLO_ENABLED
case Type::SOLO:
drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance]);
break;
#endif
#if AP_BATTMON_SMBUS_ENABLE
#if AP_BATTERY_SMBUS_GENERIC_ENABLED
case Type::SMBus_Generic:
drivers[instance] = new AP_BattMonitor_SMBus_Generic(*this, state[instance], _params[instance]);
break;
#endif
#if AP_BATTERY_SMBUS_SUI_ENABLED
case Type::SUI3:
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 3);
break;
case Type::SUI6:
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 6);
break;
#endif
#if AP_BATTERY_SMBUS_MAXELL_ENABLED
case Type::MAXELL:
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance]);
break;
#endif
#if AP_BATTERY_SMBUS_ROTOYE_ENABLED
case Type::Rotoye:
drivers[instance] = new AP_BattMonitor_SMBus_Rotoye(*this, state[instance], _params[instance]);
break;
#endif
#if AP_BATTERY_SMBUS_NEODESIGN_ENABLED
case Type::NeoDesign:
drivers[instance] = new AP_BattMonitor_SMBus_NeoDesign(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTMON_SMBUS_ENABLE
#endif
case Type::BEBOP:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
#if AP_BATTERY_BEBOP_ENABLED
drivers[instance] = new AP_BattMonitor_Bebop(*this, state[instance], _params[instance]);
#endif
break;
case Type::UAVCAN_BatteryInfo:
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED
drivers[instance] = new AP_BattMonitor_UAVCAN(*this, state[instance], AP_BattMonitor_UAVCAN::UAVCAN_BATTERY_INFO, _params[instance]);
#endif
break;
case Type::BLHeliESC:
#if HAL_WITH_ESC_TELEM && !defined(HAL_BUILD_AP_PERIPH)
#if AP_BATTERY_ESC_ENABLED
drivers[instance] = new AP_BattMonitor_ESC(*this, state[instance], _params[instance]);
#endif
break;
#if AP_BATTERY_SUM_ENABLED
case Type::Sum:
drivers[instance] = new AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance);
break;
#if AP_BATTMON_FUELFLOW_ENABLE
#endif
#if AP_BATTERY_FUELFLOW_ENABLED
case Type::FuelFlow:
drivers[instance] = new AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTMON_FUELFLOW_ENABLE
#if AP_BATTMON_FUELLEVEL_PWM_ENABLE
#endif // AP_BATTERY_FUELFLOW_ENABLED
#if AP_BATTERY_FUELLEVEL_PWM_ENABLED
case Type::FuelLevel_PWM:
drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTMON_FUELLEVEL_PWM_ENABLE
#if AP_BATTMON_FUELLEVEL_ANALOG_ENABLE
#endif // AP_BATTERY_FUELLEVEL_PWM_ENABLED
#if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
case Type::FuelLevel_Analog:
drivers[instance] = new AP_BattMonitor_FuelLevel_Analog(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTMON_FUELLEVEL_ANALOG_ENABLE
#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
#if HAL_GENERATOR_ENABLED
case Type::GENERATOR_ELEC:
drivers[instance] = new AP_BattMonitor_Generator_Elec(*this, state[instance], _params[instance]);
@ -332,12 +342,12 @@ AP_BattMonitor::init()
drivers[instance] = new AP_BattMonitor_Generator_FuelLevel(*this, state[instance], _params[instance]);
break;
#endif // HAL_GENERATOR_ENABLED
#if HAL_BATTMON_INA2XX_ENABLED
#if AP_BATTERY_INA2XX_ENABLED
case Type::INA2XX:
drivers[instance] = new AP_BattMonitor_INA2XX(*this, state[instance], _params[instance]);
break;
#endif
#if HAL_BATTMON_LTC2946_ENABLED
#if AP_BATTERY_LTC2946_ENABLED
case Type::LTC2946:
drivers[instance] = new AP_BattMonitor_LTC2946(*this, state[instance], _params[instance]);
break;
@ -347,21 +357,21 @@ AP_BattMonitor::init()
drivers[instance] = new AP_BattMonitor_Torqeedo(*this, state[instance], _params[instance]);
break;
#endif
#if AP_BATTMON_SYNTHETIC_CURRENT_ENABLED
#if AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
case Type::Analog_Volt_Synthetic_Current:
drivers[instance] = new AP_BattMonitor_Synthetic_Current(*this, state[instance], _params[instance]);
break;
#endif
#if HAL_BATTMON_INA239_ENABLED
#if AP_BATTERY_INA239_ENABLED
case Type::INA239_SPI:
drivers[instance] = new AP_BattMonitor_INA239(*this, state[instance], _params[instance]);
break;
#endif
#if HAL_EFI_ENABLED
#if AP_BATTERY_EFI_ENABLED
case Type::EFI:
drivers[instance] = new AP_BattMonitor_EFI(*this, state[instance], _params[instance]);
break;
#endif // HAL_EFI_ENABLED
#endif // AP_BATTERY_EFI_ENABLED
case Type::NONE:
default:
break;

View File

@ -1,6 +1,11 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_ANALOG_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor_Analog.h"
extern const AP_HAL::HAL& hal;
@ -103,3 +108,5 @@ bool AP_BattMonitor_Analog::has_current() const
{
return ((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT);
}
#endif // AP_BATTERY_ANALOG_ENABLED

View File

@ -1,8 +1,11 @@
#pragma once
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
#if AP_BATTERY_ANALOG_ENABLED
#include "AP_BattMonitor.h"
// default pins and dividers
#if defined(HAL_BATT_VOLT_PIN)
// pins defined in board config (hwdef.dat on ChibiOS)
@ -126,3 +129,5 @@ protected:
AP_Int8 _volt_pin; /// board pin used to measure battery voltage
AP_Int8 _curr_pin; /// board pin used to measure battery current
};
#endif // AP_BATTERY_ANALOG_ENABLED

View File

@ -13,16 +13,16 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_BEBOP_ENABLED
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
(CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO)
#include "AP_BattMonitor_Bebop.h"
#include <AP_HAL_Linux/RCOutput_Bebop.h>
#include <AP_HAL_Linux/RCOutput_Disco.h>
#include "AP_BattMonitor_Bebop.h"
#define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f)
@ -217,4 +217,4 @@ void AP_BattMonitor_Bebop::read(void)
_state.consumed_mah = capacity - (remaining * capacity) * 0.01f;
}
#endif
#endif // AP_BATTERY_BEBOP_ENABLED

View File

@ -13,15 +13,15 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_BattMonitor_EFI.h"
#include "AP_BattMonitor_config.h"
#if HAL_EFI_ENABLED
#if AP_BATTERY_EFI_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_EFI/AP_EFI.h>
extern const AP_HAL::HAL& hal;
#include "AP_BattMonitor_EFI.h"
// update state
void AP_BattMonitor_EFI::read()
@ -51,5 +51,4 @@ void AP_BattMonitor_EFI::read()
_state.last_time_micros = AP_HAL::micros();
}
#endif // HAL_EFI_ENABLED
#endif // AP_BATTERY_EFI_ENABLED

View File

@ -1,12 +1,9 @@
#pragma once
#include <AP_EFI/AP_EFI_config.h>
#if HAL_EFI_ENABLED
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
#if AP_BATTERY_EFI_ENABLED
class AP_BattMonitor_EFI : public AP_BattMonitor_Backend
{
public:
@ -25,5 +22,4 @@ public:
return true;
}
};
#endif // HAL_EFI_ENABLED
#endif // AP_BATTERY_EFI_ENABLED

View File

@ -14,13 +14,12 @@
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_ESC_ENABLED
#include "AP_BattMonitor_ESC.h"
#if HAL_WITH_ESC_TELEM
extern const AP_HAL::HAL &hal;
void AP_BattMonitor_ESC::init(void)
{
}
@ -106,4 +105,4 @@ bool AP_BattMonitor_ESC::reset_remaining(float percentage)
return false;
}
#endif // HAL_WITH_ESC_TELEM
#endif // AP_BATTERY_ESC_ENABLED

View File

@ -19,7 +19,7 @@
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include "AP_BattMonitor_Backend.h"
#if HAL_WITH_ESC_TELEM
#if AP_BATTERY_ESC_ENABLED
class AP_BattMonitor_ESC :public AP_BattMonitor_Backend
{
@ -52,4 +52,4 @@ private:
float delta_mah;
};
#endif
#endif // AP_BATTERY_ESC_ENABLED

View File

@ -1,5 +1,10 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_FUELFLOW_ENABLED
#include "AP_BattMonitor_FuelFlow.h"
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
/*
@ -122,3 +127,5 @@ void AP_BattMonitor_FuelFlow::read()
// map consumed_wh using fixed voltage of 1
_state.consumed_wh = _state.consumed_mah;
}
#endif // AP_BATTERY_FUELFLOW_ENABLED

View File

@ -1,8 +1,11 @@
#pragma once
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Analog.h"
#if AP_BATTERY_FUELFLOW_ENABLED
#include "AP_BattMonitor.h"
class AP_BattMonitor_FuelFlow : public AP_BattMonitor_Analog
{
public:
@ -32,3 +35,5 @@ private:
int8_t last_pin = -1;
};
#endif // AP_BATTERY_FUELFLOW_ENABLED

View File

@ -15,8 +15,13 @@
* Code by Charlie Johnson
*/
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor_FuelLevel_Analog.h"
extern const AP_HAL::HAL& hal;
@ -116,3 +121,5 @@ void AP_BattMonitor_FuelLevel_Analog::read()
// record time
_state.last_time_micros = tnow;
}
#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED

View File

@ -17,9 +17,12 @@
#pragma once
#include "AP_BattMonitor_Backend.h"
#if AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
#include <Filter/LowPassFilter.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend
{
@ -52,3 +55,5 @@ private:
LowPassFilterFloat _voltage_filter;
};
#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED

View File

@ -1,6 +1,10 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_FUELLEVEL_PWM_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_FuelLevel_PWM.h"
#include <GCS_MAVLink/GCS.h>
/*
"battery" monitor for liquid fuel level systems that give a PWM value indicating quantity of remaining fuel.
@ -62,3 +66,5 @@ void AP_BattMonitor_FuelLevel_PWM::read()
// map consumed_wh using fixed voltage of 1
_state.consumed_wh = _state.consumed_mah;
}
#endif // AP_BATTERY_FUELLEVEL_PWM_ENABLED

View File

@ -1,8 +1,11 @@
#pragma once
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Analog.h"
#if AP_BATTERY_FUELLEVEL_PWM_ENABLED
#include "AP_BattMonitor.h"
class AP_BattMonitor_FuelLevel_PWM : public AP_BattMonitor_Analog
{
public:
@ -25,3 +28,5 @@ private:
AP_HAL::PWMSource pwm_source;
};
#endif // AP_BATTERY_FUELLEVEL_PWM_ENABLED

View File

@ -13,14 +13,14 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_BattMonitor_Generator.h"
#include "AP_BattMonitor_config.h"
#if HAL_GENERATOR_ENABLED
#if AP_BATTERY_GENERATOR_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
extern const AP_HAL::HAL& hal;
#include "AP_BattMonitor_Generator.h"
/*
Fuel class
@ -156,4 +156,4 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Generator_Elec::update_failsafes()
}
return MAX(AP_BattMonitor_Backend::update_failsafes(), failsafe);
}
#endif
#endif // AP_BATTERY_GENERATOR_ENABLED

View File

@ -1,8 +1,11 @@
#include "AP_BattMonitor_INA239.h"
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_INA239_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_HAL/utility/sparse-endian.h>
#if HAL_BATTMON_INA239_ENABLED
#include "AP_BattMonitor_INA239.h"
extern const AP_HAL::HAL& hal;
@ -157,4 +160,4 @@ void AP_BattMonitor_INA239::timer(void)
accumulate.count++;
}
#endif // HAL_BATTMON_INA239_ENABLED
#endif // AP_BATTERY_INA239_ENABLED

View File

@ -5,11 +5,7 @@
#include "AP_BattMonitor_Backend.h"
#include <utility>
#ifndef HAL_BATTMON_INA239_ENABLED
#define HAL_BATTMON_INA239_ENABLED defined(HAL_BATTMON_INA239_SPI_DEVICE)
#endif
#if HAL_BATTMON_INA239_ENABLED
#if AP_BATTERY_INA239_ENABLED
class AP_BattMonitor_INA239 : public AP_BattMonitor_Backend
{
@ -51,4 +47,4 @@ protected:
float voltage_LSB;
};
#endif // HAL_BATTMON_INA239_ENABLED
#endif // AP_BATTERY_INA239_ENABLED

View File

@ -1,8 +1,10 @@
#include "AP_BattMonitor_INA2xx.h"
#include <GCS_MAVLink/GCS.h>
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_INA2XX_ENABLED
#include <AP_HAL/utility/sparse-endian.h>
#if HAL_BATTMON_INA2XX_ENABLED
#include "AP_BattMonitor_INA2xx.h"
extern const AP_HAL::HAL& hal;
@ -178,4 +180,4 @@ void AP_BattMonitor_INA2XX::timer(void)
accumulate.count++;
}
#endif // HAL_BATTMON_INA2XX_ENABLED
#endif // AP_BATTERY_INA2XX_ENABLED

View File

@ -6,11 +6,7 @@
#include <AP_Param/AP_Param.h>
#include <utility>
#ifndef HAL_BATTMON_INA2XX_ENABLED
#define HAL_BATTMON_INA2XX_ENABLED (BOARD_FLASH_SIZE > 1024)
#endif
#if HAL_BATTMON_INA2XX_ENABLED
#if AP_BATTERY_INA2XX_ENABLED
class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend
{
@ -56,4 +52,4 @@ private:
float voltage_LSB;
};
#endif // HAL_BATTMON_INA2XX_ENABLED
#endif // AP_BATTERY_INA2XX_ENABLED

View File

@ -1,8 +1,11 @@
#include "AP_BattMonitor_LTC2946.h"
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_LTC2946_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_HAL/utility/sparse-endian.h>
#if HAL_BATTMON_LTC2946_ENABLED
#include "AP_BattMonitor_LTC2946.h"
extern const AP_HAL::HAL& hal;
@ -107,4 +110,4 @@ void AP_BattMonitor_LTC2946::timer(void)
accumulate.count++;
}
#endif // HAL_BATTMON_LTC2946_ENABLED
#endif // AP_BATTERY_LTC2946_ENABLED

View File

@ -5,9 +5,7 @@
#include "AP_BattMonitor_Backend.h"
#include <utility>
#define HAL_BATTMON_LTC2946_ENABLED defined(HAL_BATTMON_LTC2946_BUS) && defined(HAL_BATTMON_LTC2946_ADDR)
#if HAL_BATTMON_LTC2946_ENABLED
#if AP_BATTERY_LTC2946_ENABLED
class AP_BattMonitor_LTC2946 : public AP_BattMonitor_Backend
{
@ -40,4 +38,4 @@ private:
float voltage_LSB;
};
#endif // HAL_BATTMON_LTC2946_ENABLED
#endif // AP_BATTERY_LTC2946_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_ENABLED
#include "AP_BattMonitor_SMBus.h"
#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
@ -250,3 +254,5 @@ uint8_t AP_BattMonitor_SMBus::get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool
// return result
return crc;
}
#endif // AP_BATTERY_SMBUS_ENABLED

View File

@ -1,10 +1,13 @@
#pragma once
#include "AP_BattMonitor_Backend.h"
#if AP_BATTERY_SMBUS_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_BattMonitor_Backend.h"
#include <utility>
#define AP_BATTMONITOR_SMBUS_BUS_INTERNAL 0
@ -111,3 +114,5 @@ protected:
AP_Int8 _address; // I2C address
};
#endif // AP_BATTERY_SMBUS_ENABLED

View File

@ -1,7 +1,12 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_GENERIC_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_SMBus_Generic.h"
uint8_t smbus_cell_ids[] = { 0x3f, // cell 1
@ -168,3 +173,5 @@ bool AP_BattMonitor_SMBus_Generic::check_pec_support()
_pec_confirmed = true;
return true;
}
#endif // AP_BATTERY_SMBUS_GENERIC_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus.h"
#if AP_BATTERY_SMBUS_GENERIC_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define BATTMONITOR_SMBUS_NUM_CELLS_MAX 14
#else
@ -31,3 +33,5 @@ private:
uint8_t _cell_count; // number of cells returning voltages
bool _cell_count_fixed; // true when cell count check is complete
};
#endif // AP_BATTERY_SMBUS_GENERIC_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus_Generic.h"
#if AP_BATTERY_SMBUS_MAXELL_ENABLED
class AP_BattMonitor_SMBus_Maxell : public AP_BattMonitor_SMBus_Generic
{
using AP_BattMonitor_SMBus_Generic::AP_BattMonitor_SMBus_Generic;
@ -12,3 +14,5 @@ private:
uint16_t get_capacity_scaler() const override { return 2; }
};
#endif // AP_BATTERY_SMBUS_MAXELL_ENABLED

View File

@ -1,6 +1,11 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_NEODESIGN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_SMBus_NeoDesign.h"
#define BATTMONITOR_ND_CELL_COUNT 0x5C // cell-count register
@ -75,3 +80,5 @@ void AP_BattMonitor_SMBus_NeoDesign::timer()
read_remaining_capacity();
read_temp();
}
#endif // AP_BATTERY_SMBUS_NEODESIGN_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus.h"
#if AP_BATTERY_SMBUS_NEODESIGN_ENABLED
class AP_BattMonitor_SMBus_NeoDesign : public AP_BattMonitor_SMBus
{
public:
@ -17,3 +19,5 @@ private:
static const constexpr uint8_t max_cell_count = 10;
};
#endif // AP_BATTERY_SMBUS_NEODESIGN_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_ROTOYE_ENABLED
#include "AP_BattMonitor_SMBus_Rotoye.h"
#include <AP_HAL/AP_HAL.h>
@ -25,3 +29,5 @@ void AP_BattMonitor_SMBus_Rotoye::read_temp(void) {
_state.temperature_time = AP_HAL::millis();
_state.temperature = KELVIN_TO_C(0.1f * float(MAX(t_int, t_ext)));
}
#endif // AP_BATTERY_SMBUS_ROTOYE_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus_Generic.h"
#if AP_BATTERY_SMBUS_ROTOYE_ENABLED
class AP_BattMonitor_SMBus_Rotoye : public AP_BattMonitor_SMBus_Generic
{
using AP_BattMonitor_SMBus_Generic::AP_BattMonitor_SMBus_Generic;
@ -12,3 +14,5 @@ private:
void read_temp(void) override;
};
#endif // AP_BATTERY_SMBUS_ROTOYE_ENABLED

View File

@ -1,7 +1,12 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_SUI_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_SMBus_SUI.h"
extern const AP_HAL::HAL& hal;
@ -131,3 +136,5 @@ void AP_BattMonitor_SMBus_SUI::update_health()
_state.healthy = (now - last_volt_read_us < AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) &&
(now - _state.last_time_micros < AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS);
}
#endif // AP_BATTERY_SMBUS_SUI_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus.h"
#if AP_BATTERY_SMBUS_SUI_ENABLED
// Base SUI class
class AP_BattMonitor_SMBus_SUI : public AP_BattMonitor_SMBus
{
@ -28,3 +30,5 @@ private:
bool phase_voltages;
uint32_t last_volt_read_us;
};
#endif // AP_BATTERY_SMBUS_SUI_ENABLED

View File

@ -1,10 +1,15 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SMBUS_SOLO_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_SMBus_Solo.h"
#include <utility>
#include "AP_BattMonitor_SMBus_Solo.h"
#define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register
#define BATTMONITOR_SMBUS_SOLO_CURRENT 0x2a // current register
#define BATTMONITOR_SMBUS_SOLO_BUTTON_DEBOUNCE 6 // button held down for 5 intervals will cause a power off event
@ -95,3 +100,5 @@ void AP_BattMonitor_SMBus_Solo::timer()
read_cycle_count();
}
#endif // AP_BATTERY_SMBUS_SOLO_ENABLED

View File

@ -2,6 +2,8 @@
#include "AP_BattMonitor_SMBus.h"
#if AP_BATTERY_SMBUS_SOLO_ENABLED
class AP_BattMonitor_SMBus_Solo : public AP_BattMonitor_SMBus
{
public:
@ -17,3 +19,5 @@ private:
uint8_t _button_press_count;
};
#endif // AP_BATTERY_SMBUS_SOLO_ENABLED

View File

@ -1,7 +1,12 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SUM_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Sum.h"
/*
@ -92,3 +97,5 @@ AP_BattMonitor_Sum::read()
_state.last_time_micros = tnow_us;
}
}
#endif // AP_BATTERY_SUM_ENABLED

View File

@ -1,8 +1,11 @@
#pragma once
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
#if AP_BATTERY_SUM_ENABLED
#include "AP_BattMonitor.h"
class AP_BattMonitor_Sum : public AP_BattMonitor_Backend
{
public:
@ -29,3 +32,5 @@ private:
uint8_t _instance;
bool _has_current;
};
#endif // AP_BATTERY_SUM_ENABLED

View File

@ -1,10 +1,12 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_Synthetic_Current.h"
#include <GCS_MAVLink/GCS.h>
#include <SRV_Channel/SRV_Channel.h>
#if AP_BATTMON_SYNTHETIC_CURRENT_ENABLED
/*
Analog Voltage and Current Monitor for systems with only a voltage sense pin
Current is calculated from throttle output and modified for voltage droop using
@ -70,4 +72,4 @@ AP_BattMonitor_Synthetic_Current::read()
}
#endif
#endif // AP_BATTERY_SYNTHETIC_CURRENT_ENABLED

View File

@ -3,7 +3,7 @@
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Analog.h"
#if AP_BATTMON_SYNTHETIC_CURRENT_ENABLED
#if AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
class AP_BattMonitor_Synthetic_Current : public AP_BattMonitor_Analog
{
public:

View File

@ -14,10 +14,13 @@
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_TORQEEDO_ENABLED
#include "AP_BattMonitor_Torqeedo.h"
#if HAL_TORQEEDO_ENABLED
#include <AP_HAL/AP_HAL.h>
#define AP_BATTMON_TORQEEDO_TIMEOUT_US 5000000
@ -73,4 +76,5 @@ bool AP_BattMonitor_Torqeedo::capacity_remaining_pct(uint8_t &percentage) const
return have_info;
}
#endif // HAL_TORQEEDO_ENABLED
#endif // AP_BATTERY_TORQEEDO_ENABLED

View File

@ -14,9 +14,12 @@
*/
#pragma once
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_TORQEEDO_ENABLED
#include <AP_Torqeedo/AP_Torqeedo.h>
#if HAL_TORQEEDO_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_BattMonitor_Backend.h"

View File

@ -1,7 +1,8 @@
#include "AP_BattMonitor_config.h"
#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_UAVCAN.h"
@ -466,4 +467,4 @@ uint32_t AP_BattMonitor_UAVCAN::get_mavlink_fault_bitmask() const
return mav_fault_bitmask;
}
#endif
#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED

View File

@ -1,25 +1,103 @@
#pragma once
#ifndef AP_BATTMON_SMBUS_ENABLE
#define AP_BATTMON_SMBUS_ENABLE 1
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_ESC_Telem/AP_ESC_Telem_config.h>
#include <AP_EFI/AP_EFI_config.h>
#include <AP_Generator/AP_Generator_config.h>
#include <AP_Torqeedo/AP_Torqeedo_config.h>
#ifndef AP_BATTERY_BACKEND_DEFAULT_ENABLED
#define AP_BATTERY_BACKEND_DEFAULT_ENABLED 1
#endif
#ifndef AP_BATTMON_FUELFLOW_ENABLE
#define AP_BATTMON_FUELFLOW_ENABLE (BOARD_FLASH_SIZE > 1024)
#ifndef AP_BATTERY_ANALOG_ENABLED
#define AP_BATTERY_ANALOG_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_BATTMON_FUELLEVEL_PWM_ENABLE
#define AP_BATTMON_FUELLEVEL_PWM_ENABLE (BOARD_FLASH_SIZE > 1024)
#ifndef AP_BATTERY_BEBOP_ENABLED
#define AP_BATTERY_BEBOP_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO)
#endif
#ifndef AP_BATTMON_FUELLEVEL_ANALOG_ENABLE
#define AP_BATTMON_FUELLEVEL_ANALOG_ENABLE (BOARD_FLASH_SIZE > 1024)
#ifndef AP_BATTERY_EFI_ENABLED
#define AP_BATTERY_EFI_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && HAL_EFI_ENABLED
#endif
#ifndef AP_BATTMON_SYNTHETIC_CURRENT_ENABLED
#define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 1
#ifndef AP_BATTERY_ESC_ENABLED
#define AP_BATTERY_ESC_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (HAL_WITH_ESC_TELEM && !defined(HAL_BUILD_AP_PERIPH))
#endif
#ifndef AP_BATTMON_SMBUS_SOLO_ENABLED
#define AP_BATTMON_SMBUS_SOLO_ENABLED 0 // turned on in hwdefs
#ifndef AP_BATTERY_SMBUS_ENABLED
#define AP_BATTERY_SMBUS_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED
#define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS
#endif
#ifndef AP_BATTERY_FUELFLOW_ENABLED
#define AP_BATTERY_FUELFLOW_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
#endif
#ifndef AP_BATTERY_FUELLEVEL_PWM_ENABLED
#define AP_BATTERY_FUELLEVEL_PWM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
#endif
#ifndef AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
#define AP_BATTERY_FUELLEVEL_ANALOG_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024)
#endif
#ifndef AP_BATTERY_GENERATOR_ENABLED
#define AP_BATTERY_GENERATOR_ENABLED HAL_GENERATOR_ENABLED
#endif
#ifndef AP_BATTERY_INA239_ENABLED
#define AP_BATTERY_INA239_ENABLED 0 // SPI device must be specified in hwdef
#endif
#ifndef AP_BATTERY_INA2XX_ENABLED
#define AP_BATTERY_INA2XX_ENABLED (AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024))
#endif
#ifndef AP_BATTERY_LTC2946_ENABLED
#define AP_BATTERY_LTC2946_ENABLED (AP_BATTERY_BACKEND_DEFAULT_ENABLED && defined(HAL_BATTMON_LTC2946_BUS) && defined(HAL_BATTMON_LTC2946_ADDR))
#endif
#ifndef AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
#define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_BATTERY_SMBUS_SOLO_ENABLED
#define AP_BATTERY_SMBUS_SOLO_ENABLED 0 // turned on in hwdefs
#endif
#ifndef AP_BATTERY_SUM_ENABLED
#define AP_BATTERY_SUM_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_BATTERY_TORQEEDO_ENABLED
#define AP_BATTERY_TORQEEDO_ENABLED HAL_TORQEEDO_ENABLED
#endif
// SMBus-subclass backends:
#ifndef AP_BATTERY_SMBUS_GENERIC_ENABLED
#define AP_BATTERY_SMBUS_GENERIC_ENABLED AP_BATTERY_SMBUS_ENABLED
#endif
#ifndef AP_BATTERY_SMBUS_NEODESIGN_ENABLED
#define AP_BATTERY_SMBUS_NEODESIGN_ENABLED AP_BATTERY_SMBUS_ENABLED
#endif
#ifndef AP_BATTERY_SMBUS_SUI_ENABLED
#define AP_BATTERY_SMBUS_SUI_ENABLED AP_BATTERY_SMBUS_ENABLED
#endif
// subclasses of the SUMbus generic backend:
#ifndef AP_BATTERY_SMBUS_MAXELL_ENABLED
#define AP_BATTERY_SMBUS_MAXELL_ENABLED AP_BATTERY_SMBUS_GENERIC_ENABLED
#endif
#ifndef AP_BATTERY_SMBUS_ROTOYE_ENABLED
#define AP_BATTERY_SMBUS_ROTOYE_ENABLED AP_BATTERY_SMBUS_GENERIC_ENABLED
#endif

View File

@ -0,0 +1,7 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#ifndef HAL_GENERATOR_ENABLED
#define HAL_GENERATOR_ENABLED !HAL_MINIMIZE_FEATURES && !defined(HAL_BUILD_AP_PERIPH)
#endif