Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor.h
Views: 1798
#pragma once12#include "AP_BattMonitor_config.h"34#if AP_BATTERY_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_Param/AP_Param.h>8#include <AP_Math/AP_Math.h>9#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>10#include <GCS_MAVLink/GCS_MAVLink.h>11#include "AP_BattMonitor_Params.h"1213// maximum number of battery monitors14#ifndef AP_BATT_MONITOR_MAX_INSTANCES15#define AP_BATT_MONITOR_MAX_INSTANCES 916#endif1718// first monitor is always the primary monitor19#define AP_BATT_PRIMARY_INSTANCE 02021#define AP_BATT_SERIAL_NUMBER_DEFAULT -12223#define AP_BATT_MONITOR_TIMEOUT 50002425#define AP_BATT_MONITOR_RES_EST_TC_1 0.5f26#define AP_BATT_MONITOR_RES_EST_TC_2 0.1f2728#if BOARD_FLASH_SIZE > 102429#define AP_BATT_MONITOR_CELLS_MAX 1430#else31#define AP_BATT_MONITOR_CELLS_MAX 1232#endif3334// declare backend class35class AP_BattMonitor_Backend;36class AP_BattMonitor_Analog;37class AP_BattMonitor_SMBus;38class AP_BattMonitor_SMBus_Solo;39class AP_BattMonitor_SMBus_Generic;40class AP_BattMonitor_SMBus_Maxell;41class AP_BattMonitor_SMBus_Rotoye;42class AP_BattMonitor_DroneCAN;43class AP_BattMonitor_Generator;44class AP_BattMonitor_INA2XX;45class AP_BattMonitor_INA239;46class AP_BattMonitor_LTC2946;47class AP_BattMonitor_Torqeedo;48class AP_BattMonitor_FuelLevel_Analog;49class AP_BattMonitor_EFI;50class AP_BattMonitor_Scripting;515253class AP_BattMonitor54{55friend class AP_BattMonitor_Backend;56friend class AP_BattMonitor_Analog;57friend class AP_BattMonitor_SMBus;58friend class AP_BattMonitor_SMBus_Solo;59friend class AP_BattMonitor_SMBus_Generic;60friend class AP_BattMonitor_SMBus_Maxell;61friend class AP_BattMonitor_SMBus_Rotoye;62friend class AP_BattMonitor_DroneCAN;63friend class AP_BattMonitor_Sum;64friend class AP_BattMonitor_FuelFlow;65friend class AP_BattMonitor_FuelLevel_PWM;66friend class AP_BattMonitor_Generator;67friend class AP_BattMonitor_EFI;68friend class AP_BattMonitor_INA2XX;69friend class AP_BattMonitor_INA239;70friend class AP_BattMonitor_LTC2946;71friend class AP_BattMonitor_AD7091R5;72friend class AP_BattMonitor_INA3221;7374friend class AP_BattMonitor_Torqeedo;75friend class AP_BattMonitor_FuelLevel_Analog;76friend class AP_BattMonitor_Synthetic_Current;77friend class AP_BattMonitor_Scripting;7879public:8081// battery failsafes must be defined in levels of severity so that vehicles wont fall backwards82enum class Failsafe : uint8_t {83None = 0,84Unhealthy,85Low,86Critical87};8889// Battery monitor driver types90enum class Type {91NONE = 0,92ANALOG_VOLTAGE_ONLY = 3,93ANALOG_VOLTAGE_AND_CURRENT = 4,94SOLO = 5,95BEBOP = 6,96SMBus_Generic = 7,97UAVCAN_BatteryInfo = 8,98BLHeliESC = 9,99Sum = 10,100FuelFlow = 11,101FuelLevel_PWM = 12,102SUI3 = 13,103SUI6 = 14,104NeoDesign = 15,105MAXELL = 16,106GENERATOR_ELEC = 17,107GENERATOR_FUEL = 18,108Rotoye = 19,109// 20 was MPPT_PacketDigital110INA2XX = 21,111LTC2946 = 22,112Torqeedo = 23,113FuelLevel_Analog = 24,114Analog_Volt_Synthetic_Current = 25,115INA239_SPI = 26,116EFI = 27,117AD7091R5 = 28,118Scripting = 29,119INA3221 = 30,120};121122FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t);123124AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities);125126/* Do not allow copies */127CLASS_NO_COPY(AP_BattMonitor);128129static AP_BattMonitor *get_singleton() {130return _singleton;131}132133// cell voltages in millivolts134struct cells {135uint16_t cells[AP_BATT_MONITOR_CELLS_MAX];136};137138// The BattMonitor_State structure is filled in by the backend driver139struct BattMonitor_State {140cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec141float voltage; // voltage in volts142float current_amps; // current in amperes143float consumed_mah; // total current draw in milliamp hours since start-up144float consumed_wh; // total energy consumed in Wh since start-up145uint32_t last_time_micros; // time when voltage and current was last read in microseconds146uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum in milliseconds147uint32_t critical_voltage_start_ms; // critical voltage failsafe start timer in milliseconds148float temperature; // battery temperature in degrees Celsius149#if AP_TEMPERATURE_SENSOR_ENABLED150bool temperature_external_use;151float temperature_external; // battery temperature set by an external source in degrees Celsius152#endif153uint32_t temperature_time; // timestamp of the last received temperature message154float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate in Volt155float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage156Failsafe failsafe; // stage failsafe the battery is in157bool healthy; // battery monitor is communicating correctly158uint32_t last_healthy_ms; // Time when monitor was last healthy159bool is_powering_off; // true when power button commands power off160bool powerOffNotified; // only send powering off notification once161uint32_t time_remaining; // remaining battery time162bool has_time_remaining; // time_remaining is only valid if this is true163uint8_t state_of_health_pct; // state of health (SOH) in percent164bool has_state_of_health_pct; // state_of_health_pct is only valid if this is true165uint8_t instance; // instance number of this backend166Type type; // allocated instance type167const struct AP_Param::GroupInfo *var_info;168};169170static const struct AP_Param::GroupInfo *backend_var_info[AP_BATT_MONITOR_MAX_INSTANCES];171172// Return the number of battery monitor instances173uint8_t num_instances(void) const { return _num_instances; }174175// detect and initialise any available battery monitors176void init();177178/// Read the battery voltage and current for all batteries. Should be called at 10hz179void read();180181// healthy - returns true if monitor is functioning182bool healthy(uint8_t instance) const;183184// return true if all configured battery monitors are healthy185bool healthy() const;186187/// voltage - returns battery voltage in volts188float voltage(uint8_t instance) const;189float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }190191// voltage for a GCS, may be resistance compensated192float gcs_voltage(uint8_t instance) const;193float gcs_voltage(void) const { return gcs_voltage(AP_BATT_PRIMARY_INSTANCE); }194195/// get voltage with sag removed (based on battery current draw and resistance)196/// this will always be greater than or equal to the raw voltage197float voltage_resting_estimate(uint8_t instance) const;198float voltage_resting_estimate() const { return voltage_resting_estimate(AP_BATT_PRIMARY_INSTANCE); }199200/// current_amps - returns the instantaneous current draw in amperes201bool current_amps(float ¤t, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;202203/// consumed_mah - returns total current drawn since start-up in milliampere.hours204bool consumed_mah(float &mah, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;205206/// consumed_wh - returns total energy drawn since start-up in watt.hours207bool consumed_wh(float&wh, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;208209/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument210virtual bool capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const WARN_IF_UNUSED;211bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED { return capacity_remaining_pct(percentage, AP_BATT_PRIMARY_INSTANCE); }212213/// time_remaining - returns remaining battery time214bool time_remaining(uint32_t &seconds, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;215216/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full217int32_t pack_capacity_mah(uint8_t instance) const;218int32_t pack_capacity_mah() const { return pack_capacity_mah(AP_BATT_PRIMARY_INSTANCE); }219220/// returns true if a battery failsafe has ever been triggered221bool has_failsafed(void) const { return _has_triggered_failsafe; };222223/// returns the highest failsafe action that has been triggered224int8_t get_highest_failsafe_priority(void) const { return _highest_failsafe_priority; };225226/// configured_type - returns battery monitor type as configured in parameters227enum Type configured_type(uint8_t instance) const {228return (Type)_params[instance]._type.get();229}230/// allocated_type - returns battery monitor type as allocated231enum Type allocated_type(uint8_t instance) const {232return state[instance].type;233}234235/// get_serial_number - returns battery serial number236int32_t get_serial_number() const { return get_serial_number(AP_BATT_PRIMARY_INSTANCE); }237int32_t get_serial_number(uint8_t instance) const {238return _params[instance]._serial_number;239}240241/// true when (voltage * current) > watt_max242bool overpower_detected() const;243bool overpower_detected(uint8_t instance) const;244245// cell voltages in millivolts246bool has_cell_voltages() const { return has_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }247bool has_cell_voltages(const uint8_t instance) const;248const cells &get_cell_voltages() const { return get_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }249const cells &get_cell_voltages(const uint8_t instance) const;250251// get once cell voltage (for scripting)252bool get_cell_voltage(uint8_t instance, uint8_t cell, float &voltage) const;253254// temperature255bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); }256bool get_temperature(float &temperature, const uint8_t instance) const;257#if AP_TEMPERATURE_SENSOR_ENABLED258bool set_temperature(const float temperature, const uint8_t instance);259bool set_temperature_by_serial_number(const float temperature, const int32_t serial_number);260#endif261262// MPPT Control (Solar panels)263void MPPT_set_powered_state_to_all(const bool power_on);264void MPPT_set_powered_state(const uint8_t instance, const bool power_on);265266bool option_is_set(uint8_t instance, AP_BattMonitor_Params::Options option) const;267268// cycle count269bool get_cycle_count(uint8_t instance, uint16_t &cycles) const;270271// get battery resistance estimate in ohms272float get_resistance() const { return get_resistance(AP_BATT_PRIMARY_INSTANCE); }273float get_resistance(uint8_t instance) const { return state[instance].resistance; }274275// returns false if we fail arming checks, in which case the buffer will be populated with a failure message276bool arming_checks(size_t buflen, char *buffer) const;277278// sends powering off mavlink broadcasts and sets notify flag279void checkPoweringOff(void);280281// reset battery remaining percentage282bool reset_remaining_mask(uint16_t battery_mask, float percentage);283bool reset_remaining(uint8_t instance, float percentage) { return reset_remaining_mask(1U<<instance, percentage);}284285// Returns mavlink charge state286MAV_BATTERY_CHARGE_STATE get_mavlink_charge_state(const uint8_t instance) const;287288// Returns mavlink fault state289uint32_t get_mavlink_fault_bitmask(const uint8_t instance) const;290291// return true if state of health (as a percentage) can be provided and fills in soh_pct argument292bool get_state_of_health_pct(uint8_t instance, uint8_t &soh_pct) const;293294static const struct AP_Param::GroupInfo var_info[];295296#if AP_BATTERY_SCRIPTING_ENABLED297bool handle_scripting(uint8_t idx, const struct BattMonitorScript_State &state);298#endif299300protected:301302/// parameters303AP_BattMonitor_Params _params[AP_BATT_MONITOR_MAX_INSTANCES];304305private:306static AP_BattMonitor *_singleton;307308BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES];309AP_BattMonitor_Backend *drivers[AP_BATT_MONITOR_MAX_INSTANCES];310uint32_t _log_battery_bit;311uint8_t _num_instances; /// number of monitors312313void convert_dynamic_param_groups(uint8_t instance);314315/// returns the failsafe state of the battery316Failsafe check_failsafe(const uint8_t instance);317void check_failsafes(void); // checks all batteries failsafes318319battery_failsafe_handler_fn_t _battery_failsafe_handler_fn;320const int8_t *_failsafe_priorities; // array of failsafe priorities, sorted highest to lowest priority, -1 indicates no more entries321322int8_t _highest_failsafe_priority; // highest selected failsafe action level (used to restrict what actions we move into)323bool _has_triggered_failsafe; // true after a battery failsafe has been triggered for the first time324325};326327namespace AP {328AP_BattMonitor &battery();329};330331#endif // AP_BATTERY_ENABLED332333334