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_Backend.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once1516#include "AP_BattMonitor_config.h"1718#if AP_BATTERY_ENABLED1920#include "AP_BattMonitor.h"2122#include <AP_Common/AP_Common.h>2324class AP_BattMonitor_Backend25{26public:27// constructor. This incorporates initialisation as well.28AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms);2930// we declare a virtual destructor so that BattMonitor driver can31// override with a custom destructor if need be32virtual ~AP_BattMonitor_Backend(void) {}3334// initialise35virtual void init() {};3637// read the latest battery voltage38virtual void read() = 0;3940/// returns true if battery monitor instance provides time remaining info41virtual bool has_time_remaining() const { return false; }4243/// returns true if battery monitor instance provides consumed energy info44virtual bool has_consumed_energy() const { return false; }4546/// returns true if battery monitor instance provides current info47virtual bool has_current() const = 0;4849// returns true if battery monitor provides individual cell voltages50virtual bool has_cell_voltages() const { return false; }5152// returns true if battery monitor provides temperature53virtual bool has_temperature() const { return false; }5455// returns true if temperature retrieved successfully56virtual bool get_temperature(float &temperature) const;5758// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument59// returns false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small60virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED;6162// return true if cycle count can be provided and fills in cycles argument63virtual bool get_cycle_count(uint16_t &cycles) const { return false; }6465// return true if state of health (as a percentage) can be provided and fills in soh_pct argument66bool get_state_of_health_pct(uint8_t &soh_pct) const;6768/// get voltage with sag removed (based on battery current draw and resistance)69/// this will always be greater than or equal to the raw voltage70float voltage_resting_estimate() const;7172// update battery resistance estimate and voltage_resting_estimate73virtual void update_resistance_estimate();7475// updates failsafe timers, and returns what failsafes are active76virtual AP_BattMonitor::Failsafe update_failsafes(void);7778// returns false if we fail arming checks, in which case the buffer will be populated with a failure message79bool arming_checks(char * buffer, size_t buflen) const;8081// reset remaining percentage to given value82virtual bool reset_remaining(float percentage);8384// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)85virtual uint32_t get_mavlink_fault_bitmask() const { return 0; }8687// logging functions88void Log_Write_BAT(const uint8_t instance, const uint64_t time_us) const;89void Log_Write_BCL(const uint8_t instance, const uint64_t time_us) const;9091// set desired MPPT powered state (enabled/disabled)92virtual void mppt_set_powered_state(bool power_on) {};9394// Update an ESC telemetry channel's power information95void update_esc_telem_outbound();9697// amps: current (A)98// dt_us: time between samples (micro-seconds)99static float calculate_mah(float amps, float dt_us) { return (float) (amps * dt_us * AUS_TO_MAH); }100101// check if a option is set102bool option_is_set(const AP_BattMonitor_Params::Options option) const {103return (uint16_t(_params._options.get()) & uint16_t(option)) != 0;104}105106#if AP_BATTERY_SCRIPTING_ENABLED107virtual bool handle_scripting(const BattMonitorScript_State &battmon_state) { return false; }108#endif109110protected:111AP_BattMonitor &_mon; // reference to front-end112AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)113AP_BattMonitor_Params &_params; // reference to this instances parameters (held in the front-end)114115// checks what failsafes could be triggered116void check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const;117void update_consumed(AP_BattMonitor::BattMonitor_State &state, uint32_t dt_us);118119private:120// resistance estimate121uint32_t _resistance_timer_ms; // system time of last resistance estimate update122float _voltage_filt; // filtered voltage123float _current_max_amps; // maximum current since start-up124float _current_filt_amps; // filtered current125float _resistance_voltage_ref; // voltage used for maximum resistance calculation126float _resistance_current_ref; // current used for maximum resistance calculation127};128129#if AP_BATTERY_SCRIPTING_ENABLED130struct BattMonitorScript_State {131float voltage; // Battery voltage in volts132bool healthy; // True if communicating properly133uint8_t cell_count; // Number of valid cells in state134uint8_t capacity_remaining_pct=UINT8_MAX; // Remaining battery capacity in percent, 255 for invalid135uint16_t cell_voltages[32]; // allow script to have up to 32 cells, will be limited internally136uint16_t cycle_count=UINT16_MAX; // Battery cycle count, 65535 for unavailable137/*138all of the following float variables should be set to NaN by the139script if they are not known.140consumed_mah will auto-integrate if set to NaN141*/142float current_amps=nanf(""); // Battery current in amperes143float consumed_mah=nanf(""); // Total current drawn since start-up in milliampere hours144float consumed_wh=nanf(""); // Total energy drawn since start-up in watt hours145float temperature=nanf(""); // Battery temperature in degrees Celsius146};147#endif // AP_BATTERY_SCRIPTING_ENABLED148149#endif // AP_BATTERY_ENABLED150151152