35 _log_battery_bit(log_battery_bit),
37 _battery_failsafe_handler_fn(battery_failsafe_handler_fn),
38 _failsafe_priorities(failsafe_priorities)
61 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO 69 memset(&
state[instance].cell_voltages, 0xFF,
sizeof(
cells));
90 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO 107 if (
drivers[instance] !=
nullptr) {
114 if (
_params[0]._type.configured_in_storage()) {
119 #define SECOND_BATT_CONVERT_MASK 0x80 120 const struct ConversionTable {
123 }conversionTable[22] = {
153 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 155 #elif APM_BUILD_TYPE(APM_BUILD_ArduCopter) 157 #elif APM_BUILD_TYPE(APM_BUILD_ArduSub) 159 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) 166 for (uint8_t i = 0; i <
ARRAY_SIZE(conversionTable); i++) {
167 uint8_t param_instance = conversionTable[i].new_index >> 7;
168 uint8_t destination_index = 0x7F & conversionTable[i].new_index;
172 if (param_instance) {
310 if (type <=
state[i].failsafe) {
315 const char *type_str =
nullptr;
325 type_str =
"critical";
329 gcs().
send_text(MAV_SEVERITY_WARNING,
"Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
369 switch (
_params[instance].failsafe_voltage_source()) {
380 if ((voltage_used > 0) && (
_params[instance]._critical_voltage > 0) && (voltage_used <
_params[instance]._critical_voltage)) {
382 if (
state[instance].critical_voltage_start_ms == 0) {
384 }
else if (
_params[instance]._low_voltage_timeout > 0 &&
385 now -
state[instance].critical_voltage_start_ms > uint32_t(
_params[instance]._low_voltage_timeout)*1000U) {
399 if ((voltage_used > 0) && (
_params[instance]._low_voltage > 0) && (voltage_used <
_params[instance]._low_voltage)) {
401 if (
state[instance].low_voltage_start_ms == 0) {
403 }
else if (
_params[instance]._low_voltage_timeout > 0 &&
404 now -
state[instance].low_voltage_start_ms > uint32_t(
_params[instance]._low_voltage_timeout)*1000U) {
414 ((
_params[instance]._pack_capacity -
state[instance].consumed_mah) <
_params[instance]._low_capacity)) {
426 for (uint8_t instance = 0; instance <
_num_instances; instance++) {
434 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
bool get_soft_armed() const
#define AP_BATTMONITOR_SMBUS_BUS_EXTERNAL
const int8_t * _failsafe_priorities
static const struct AP_Param::GroupInfo var_info[]
#define AP_BATT_MONITOR_TIMEOUT
int8_t _highest_failsafe_priority
bool _has_triggered_failsafe
BatteryFailsafe check_failsafe(const uint8_t instance)
returns the failsafe state of the battery
#define AP_BATT_PRIMARY_INSTANCE
Interface definition for the various Ground Control System.
bool should_log(uint32_t mask) const
#define AP_BATTMONITOR_SMBUS_I2C_ADDR
uint32_t critical_voltage_start_ms
static AP_BattMonitor & battery()
AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities)
float voltage_resting_estimate() const
static const struct AP_Param::GroupInfo var_info[]
#define AP_SUBGROUPINFO_FLAGS(element, name, idx, thisclazz, elclazz, flags)
bool overpower_detected() const
true when (voltage * current) > watt_max
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
uint32_t _log_battery_bit
AP_BattMonitor_Params _params[AP_BATT_MONITOR_MAX_INSTANCES]
parameters
AP_Int32 _pack_capacity
offset voltage that is subtracted from current pin before conversion to amps
friend class AP_BattMonitor_SMBus_Solo
AP_BattMonitor_Backend * drivers[AP_BATT_MONITOR_MAX_INSTANCES]
battery_failsafe_handler_fn_t _battery_failsafe_handler_fn
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES]
AP_Int16 _watt_max
battery pack capacity less reserve in mAh
friend class AP_BattMonitor_UAVCAN
static DataFlash_Class * instance(void)
uint32_t failsafe_battery
float current_amps() const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
uint32_t low_voltage_start_ms
#define AP_BATTMONITOR_SMBUS_BUS_INTERNAL
virtual bool has_current() const =0
returns true if battery monitor instance provides current info
uint8_t capacity_remaining_pct() const
AP_HAL::I2CDeviceManager * i2c_mgr
#define SECOND_BATT_CONVERT_MASK
uint8_t capacity_remaining_pct() const
capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
#define AP_PARAM_FLAG_IGNORE_ENABLE
void Log_Write_Power(void)
int snprintf(char *str, size_t size, const char *format,...)
static struct notify_flags_and_values_type flags
AP_Int8 _failsafe_low_action
capacity level used to trigger a critical battery failsafe
uint32_t old_group_element
virtual bool has_consumed_energy() const
returns true if battery monitor instance provides consumed energy info
void read()
Read the battery voltage and current for all batteries. Should be called at 10hz. ...
static AP_BattMonitor * _singleton
int32_t pack_capacity_mah() const
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
bool get_temperature(float &temperature) const
void check_failsafes(void)
friend class AP_BattMonitor_Analog
friend class AP_BattMonitor_SMBus_Maxell
void update_resistance_estimate()
enum AP_BattMonitor_Params::BattMonitor_Type get_type()
get_type - returns battery monitor type
bool has_consumed_energy() const
void panic(const char *errormsg,...) FMT_PRINTF(1
float consumed_wh() const
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
void convert_params(void)
number of monitors
AP_Int8 _failsafe_critical_action
action to preform on a low battery failsafe
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
#define AP_BATT_MONITOR_MAX_INSTANCES
float consumed_mah() const
const cells & get_cell_voltages() const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
virtual bool has_cell_voltages() const