APM:Libraries
AP_BattMonitor.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Param/AP_Param.h>
5 #include <AP_Math/AP_Math.h>
8 
9 // maximum number of battery monitors
10 #define AP_BATT_MONITOR_MAX_INSTANCES 2
11 
12 // first monitor is always the primary monitor
13 #define AP_BATT_PRIMARY_INSTANCE 0
14 
15 #define AP_BATT_SERIAL_NUMBER_DEFAULT -1
16 
17 #define AP_BATT_MONITOR_TIMEOUT 5000
18 
19 #define AP_BATT_MONITOR_RES_EST_TC_1 0.5f
20 #define AP_BATT_MONITOR_RES_EST_TC_2 0.1f
21 
22 // declare backend class
29 
31 {
32  friend class AP_BattMonitor_Backend;
33  friend class AP_BattMonitor_Analog;
34  friend class AP_BattMonitor_SMBus;
37  friend class AP_BattMonitor_UAVCAN;
38 
39 public:
40 
41  // battery failsafes must be defined in levels of severity so that vehicles wont fall backwards
46  };
47 
48  FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t);
49 
50  AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities);
51 
52  /* Do not allow copies */
53  AP_BattMonitor(const AP_BattMonitor &other) = delete;
54  AP_BattMonitor &operator=(const AP_BattMonitor&) = delete;
55 
56  static AP_BattMonitor &battery() {
57  return *_singleton;
58  }
59 
60  struct cells {
61  uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
62  };
63 
64  // The BattMonitor_State structure is filled in by the backend driver
66  cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec
67  float voltage; // voltage in volts
68  float current_amps; // current in amperes
69  float consumed_mah; // total current draw in milliamp hours since start-up
70  float consumed_wh; // total energy consumed in Wh since start-up
71  uint32_t last_time_micros; // time when voltage and current was last read in microseconds
72  uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum in milliseconds
73  uint32_t critical_voltage_start_ms; // critical voltage failsafe start timer in milliseconds
74  float temperature; // battery temperature in degrees Celsius
75  uint32_t temperature_time; // timestamp of the last received temperature message
76  float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate in Volt
77  float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage
78  BatteryFailsafe failsafe; // stage failsafe the battery is in
79  bool healthy; // battery monitor is communicating correctly
80  };
81 
82  // Return the number of battery monitor instances
83  uint8_t num_instances(void) const { return _num_instances; }
84 
85  // detect and initialise any available battery monitors
86  void init();
87 
89  void read();
90 
91  // healthy - returns true if monitor is functioning
92  bool healthy(uint8_t instance) const;
93  bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); }
94 
96  bool has_consumed_energy(uint8_t instance) const;
98 
100  bool has_current(uint8_t instance) const;
102 
104  float voltage(uint8_t instance) const;
105  float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }
106 
109  float voltage_resting_estimate(uint8_t instance) const;
111 
113  float current_amps(uint8_t instance) const;
115 
117  float consumed_mah(uint8_t instance) const;
119 
121  float consumed_wh(uint8_t instance) const;
123 
125  virtual uint8_t capacity_remaining_pct(uint8_t instance) const;
127 
129  int32_t pack_capacity_mah(uint8_t instance) const;
131 
133  BatteryFailsafe check_failsafe(const uint8_t instance);
134  void check_failsafes(void); // checks all batteries failsafes
135 
137  bool has_failsafed(void) const { return _has_triggered_failsafe; };
138 
141 
144  enum AP_BattMonitor_Params::BattMonitor_Type get_type(uint8_t instance) { return _params[instance].type(); }
145 
147  void set_monitoring(uint8_t instance, uint8_t mon) { _params[instance]._type.set(mon); }
148 
150  bool overpower_detected() const;
151  bool overpower_detected(uint8_t instance) const;
152 
153  // cell voltages
155  bool has_cell_voltages(const uint8_t instance) const;
157  const cells & get_cell_voltages(const uint8_t instance) const;
158 
159  // temperature
160  bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); };
161  bool get_temperature(float &temperature, const uint8_t instance) const;
162 
163  // get battery resistance estimate in ohms
165  float get_resistance(uint8_t instance) const { return state[instance].resistance; }
166 
167  static const struct AP_Param::GroupInfo var_info[];
168 
169 protected:
170 
173 
174 private:
176 
180  uint8_t _num_instances;
181 
182  void convert_params(void);
183 
184  battery_failsafe_handler_fn_t _battery_failsafe_handler_fn;
185  const int8_t *_failsafe_priorities; // array of failsafe priorities, sorted highest to lowest priority, -1 indicates no more entries
186 
187  int8_t _highest_failsafe_priority; // highest selected failsafe action level (used to restrict what actions we move into)
188  bool _has_triggered_failsafe; // true after a battery failsafe has been triggered for the first time
189 
190 };
191 
192 namespace AP {
194 };
const int8_t * _failsafe_priorities
static const struct AP_Param::GroupInfo var_info[]
int8_t _highest_failsafe_priority
bool _has_triggered_failsafe
BatteryFailsafe check_failsafe(const uint8_t instance)
returns the failsafe state of the battery
float get_resistance(uint8_t instance) const
#define AP_BATT_PRIMARY_INSTANCE
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
bool has_cell_voltages()
int8_t get_highest_failsafe_priority(void) const
returns the highest failsafe action that has been triggered
FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t)
bool overpower_detected() const
true when (voltage * current) > watt_max
uint32_t _log_battery_bit
BattMonitor_Type type(void) const
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
AP_BattMonitor_Params _params[AP_BATT_MONITOR_MAX_INSTANCES]
parameters
AP_BattMonitor_Backend * drivers[AP_BATT_MONITOR_MAX_INSTANCES]
Definition: AP_AHRS.cpp:486
battery_failsafe_handler_fn_t _battery_failsafe_handler_fn
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES]
float voltage() const
uint8_t _num_instances
void set_monitoring(uint8_t instance, uint8_t mon)
set_monitoring - sets the monitor type (used for example sketch only)
float current_amps() const
uint8_t capacity_remaining_pct() const
Common definitions and utility routines for the ArduPilot libraries.
AP_BattMonitor & operator=(const AP_BattMonitor &)=delete
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
bool has_current() const
bool get_temperature(float &temperature) const
void check_failsafes(void)
enum AP_BattMonitor_Params::BattMonitor_Type get_type()
get_type - returns battery monitor type
bool has_consumed_energy() const
float consumed_wh() const
void convert_params(void)
number of monitors
uint8_t num_instances(void) const
#define AP_BATT_MONITOR_MAX_INSTANCES
float get_resistance() const
float consumed_mah() const
bool has_failsafed(void) const
returns true if a battery failsafe has ever been triggered
bool healthy() const
const cells & get_cell_voltages() const