APM:Libraries
AP_BattMonitor.cpp
Go to the documentation of this file.
1 #include "AP_BattMonitor.h"
3 #include "AP_BattMonitor_SMBus.h"
4 #include "AP_BattMonitor_Bebop.h"
5 #if HAL_WITH_UAVCAN
7 #endif
9 #include <DataFlash/DataFlash.h>
10 #include <GCS_MAVLink/GCS.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
15 
17  // 0 - 18, 20- 22 used by old parameter indexes
18 
19  // @Group: _
20  // @Path: AP_BattMonitor_Params.cpp
22 
23  // @Group: 2_
24  // @Path: AP_BattMonitor_Params.cpp
26 
28 };
29 
30 // Default constructor.
31 // Note that the Vector/Matrix constructors already implicitly zero
32 // their values.
33 //
34 AP_BattMonitor::AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities) :
35  _log_battery_bit(log_battery_bit),
36  _num_instances(0),
37  _battery_failsafe_handler_fn(battery_failsafe_handler_fn),
38  _failsafe_priorities(failsafe_priorities)
39 {
41 
42  if (_singleton != nullptr) {
43  AP_HAL::panic("AP_BattMonitor must be singleton");
44  }
45  _singleton = this;
46 }
47 
48 // init - instantiate the battery monitors
49 void
51 {
52  // check init has not been called before
53  if (_num_instances != 0) {
54  return;
55  }
56 
57  _highest_failsafe_priority = INT8_MAX;
58 
60 
61 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
62  // force monitor for bebop
64 #endif
65 
66  // create each instance
67  for (uint8_t instance=0; instance<AP_BATT_MONITOR_MAX_INSTANCES; instance++) {
68  // clear out the cell voltages
69  memset(&state[instance].cell_voltages, 0xFF, sizeof(cells));
70 
71  switch (get_type(instance)) {
74  drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]);
76  break;
78  drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance],
80  100000, true, 20));
82  break;
84  drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance],
86  100000, true, 20));
87  _num_instances++;
88  break;
90 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
91  drivers[instance] = new AP_BattMonitor_Bebop(*this, state[instance], _params[instance]);
92  _num_instances++;
93 #endif
94  break;
96 #if HAL_WITH_UAVCAN
97  drivers[instance] = new AP_BattMonitor_UAVCAN(*this, state[instance], AP_BattMonitor_UAVCAN::UAVCAN_BATTERY_INFO, _params[instance]);
98  _num_instances++;
99 #endif
100  break;
102  default:
103  break;
104  }
105 
106  // call init function for each backend
107  if (drivers[instance] != nullptr) {
108  drivers[instance]->init();
109  }
110  }
111 }
112 
114  if (_params[0]._type.configured_in_storage()) {
115  // _params[0]._type will always be configured in storage after conversion is done the first time
116  return;
117  }
118 
119  #define SECOND_BATT_CONVERT_MASK 0x80
120  const struct ConversionTable {
121  uint8_t old_element;
122  uint8_t new_index; // upper bit used to indicate if its the first or second instance
123  }conversionTable[22] = {
124  { 0, 0 }, // _MONITOR
125  { 1, 1 }, // _VOLT_PIN
126  { 2, 2 }, // _CURR_PIN
127  { 3, 3 }, // _VOLT_MULT
128  { 4, 4 }, // _AMP_PERVOLT
129  { 5, 5 }, // _AMP_OFFSET
130  { 6, 6 }, // _CAPACITY
131  { 9, 7 }, // _WATT_MAX
132  {10, 8 }, // _SERIAL_NUM
133  {11, (SECOND_BATT_CONVERT_MASK | 0)}, // 2_MONITOR
134  {12, (SECOND_BATT_CONVERT_MASK | 1)}, // 2_VOLT_PIN
135  {13, (SECOND_BATT_CONVERT_MASK | 2)}, // 2_CURR_PIN
136  {14, (SECOND_BATT_CONVERT_MASK | 3)}, // 2_VOLT_MULT
137  {15, (SECOND_BATT_CONVERT_MASK | 4)}, // 2_AMP_PERVOLT
138  {16, (SECOND_BATT_CONVERT_MASK | 5)}, // 2_AMP_OFFSET
139  {17, (SECOND_BATT_CONVERT_MASK | 6)}, // 2_CAPACITY
140  {18, (SECOND_BATT_CONVERT_MASK | 7)}, // 2_WATT_MAX
141  {20, (SECOND_BATT_CONVERT_MASK | 8)}, // 2_SERIAL_NUM
142  {21, 9 }, // _LOW_TIMER
143  {22, 10 }, // _LOW_TYPE
144  {21, (SECOND_BATT_CONVERT_MASK | 9)}, // 2_LOW_TIMER
145  {22, (SECOND_BATT_CONVERT_MASK |10)}, // 2_LOW_TYPE
146  };
147 
148 
149  char param_name[17];
151  info.new_name = param_name;
152 
153 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
154  info.old_key = 166;
155 #elif APM_BUILD_TYPE(APM_BUILD_ArduCopter)
156  info.old_key = 36;
157 #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
158  info.old_key = 33;
159 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
160  info.old_key = 145;
161 #else
162  _params[0]._type.save(true);
163  return; // no conversion is supported on this platform
164 #endif
165 
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;
169 
170  info.old_group_element = conversionTable[i].old_element;
171  info.type = (ap_var_type)AP_BattMonitor_Params::var_info[destination_index].type;
172  if (param_instance) {
173  hal.util->snprintf(param_name, 17, "BATT2_%s", AP_BattMonitor_Params::var_info[destination_index].name);
174  } else {
175  hal.util->snprintf(param_name, 17, "BATT_%s", AP_BattMonitor_Params::var_info[destination_index].name);
176  }
177 
178  AP_Param::convert_old_parameter(&info, 1.0f, 0);
179  }
180 
181  // force _params[0]._type into storage to flag that conversion has been done
182  _params[0]._type.save(true);
183 }
184 
185 // read - read the voltage and current for all instances
186 void
188 {
189  for (uint8_t i=0; i<_num_instances; i++) {
190  if (drivers[i] != nullptr && _params[i].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
191  drivers[i]->read();
193  }
194  }
195 
198  }
199 
201  if (df->should_log(_log_battery_bit)) {
202  df->Log_Write_Current();
203  df->Log_Write_Power();
204  }
205 
206  check_failsafes();
207 }
208 
209 // healthy - returns true if monitor is functioning
210 bool AP_BattMonitor::healthy(uint8_t instance) const {
211  return instance < _num_instances && state[instance].healthy;
212 }
213 
215 bool AP_BattMonitor::has_consumed_energy(uint8_t instance) const
216 {
217  if (instance < _num_instances && drivers[instance] != nullptr && _params[instance].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
218  return drivers[instance]->has_consumed_energy();
219  }
220 
221  // not monitoring current
222  return false;
223 }
224 
226 bool AP_BattMonitor::has_current(uint8_t instance) const
227 {
228  if (instance < _num_instances && drivers[instance] != nullptr && _params[instance].type() != AP_BattMonitor_Params::BattMonitor_TYPE_NONE) {
229  return drivers[instance]->has_current();
230  }
231 
232  // not monitoring current
233  return false;
234 }
235 
237 float AP_BattMonitor::voltage(uint8_t instance) const
238 {
239  if (instance < _num_instances) {
240  return state[instance].voltage;
241  } else {
242  return 0.0f;
243  }
244 }
245 
248 float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const
249 {
250  if (instance < _num_instances) {
251  // resting voltage should always be greater than or equal to the raw voltage
252  return MAX(state[instance].voltage, state[instance].voltage_resting_estimate);
253  } else {
254  return 0.0f;
255  }
256 }
257 
259 float AP_BattMonitor::current_amps(uint8_t instance) const {
260  if (instance < _num_instances) {
261  return state[instance].current_amps;
262  } else {
263  return 0.0f;
264  }
265 }
266 
268 float AP_BattMonitor::consumed_mah(uint8_t instance) const {
269  if (instance < _num_instances) {
270  return state[instance].consumed_mah;
271  } else {
272  return 0.0f;
273  }
274 }
275 
277 float AP_BattMonitor::consumed_wh(uint8_t instance) const {
278  if (instance < _num_instances) {
279  return state[instance].consumed_wh;
280  } else {
281  return 0.0f;
282  }
283 }
284 
286 uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
287 {
288  if (instance < _num_instances && drivers[instance] != nullptr) {
289  return drivers[instance]->capacity_remaining_pct();
290  } else {
291  return 0;
292  }
293 }
294 
296 int32_t AP_BattMonitor::pack_capacity_mah(uint8_t instance) const
297 {
298  if (instance < AP_BATT_MONITOR_MAX_INSTANCES) {
299  return _params[instance]._pack_capacity;
300  } else {
301  return 0;
302  }
303 }
304 
306 {
307  if (hal.util->get_soft_armed()) {
308  for (uint8_t i = 0; i < _num_instances; i++) {
309  const BatteryFailsafe type = check_failsafe(i);
310  if (type <= state[i].failsafe) {
311  continue;
312  }
313 
314  int8_t action = 0;
315  const char *type_str = nullptr;
316  switch (type) {
318  continue; // should not have been called in this case
320  action = _params[i]._failsafe_low_action;
321  type_str = "low";
322  break;
325  type_str = "critical";
326  break;
327  }
328 
329  gcs().send_text(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
330  (double)voltage(i), (double)consumed_mah(i));
333  state[i].failsafe = type;
334 
335  // map the desired failsafe action to a prioritiy level
336  int8_t priority = 0;
337  if (_failsafe_priorities != nullptr) {
338  while (_failsafe_priorities[priority] != -1) {
339  if (_failsafe_priorities[priority] == action) {
340  break;
341  }
342  priority++;
343  }
344 
345  }
346 
347  // trigger failsafe if the action was equal or higher priority
348  // It's valid to retrigger the same action if a different battery provoked the event
349  if (priority <= _highest_failsafe_priority) {
350  _battery_failsafe_handler_fn(type_str, action);
351  _highest_failsafe_priority = priority;
352  }
353  }
354  }
355 }
356 
357 // returns the failsafe state of the battery
359 {
360  // exit immediately if no monitors setup
361  if (_num_instances == 0 || instance >= _num_instances) {
362  return BatteryFailsafe_None;
363  }
364 
365  const uint32_t now = AP_HAL::millis();
366 
367  // use voltage or sag compensated voltage
368  float voltage_used;
369  switch (_params[instance].failsafe_voltage_source()) {
371  default:
372  voltage_used = state[instance].voltage;
373  break;
375  voltage_used = voltage_resting_estimate(instance);
376  break;
377  }
378 
379  // check critical battery levels
380  if ((voltage_used > 0) && (_params[instance]._critical_voltage > 0) && (voltage_used < _params[instance]._critical_voltage)) {
381  // this is the first time our voltage has dropped below minimum so start timer
382  if (state[instance].critical_voltage_start_ms == 0) {
383  state[instance].critical_voltage_start_ms = now;
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) {
387  }
388  } else {
389  // acceptable voltage so reset timer
390  state[instance].critical_voltage_start_ms = 0;
391  }
392 
393  // check capacity if current monitoring is enabled
394  if (has_current(instance) && (_params[instance]._critical_capacity > 0) &&
395  ((_params[instance]._pack_capacity - state[instance].consumed_mah) < _params[instance]._critical_capacity)) {
397  }
398 
399  if ((voltage_used > 0) && (_params[instance]._low_voltage > 0) && (voltage_used < _params[instance]._low_voltage)) {
400  // this is the first time our voltage has dropped below minimum so start timer
401  if (state[instance].low_voltage_start_ms == 0) {
402  state[instance].low_voltage_start_ms = now;
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) {
405  return BatteryFailsafe_Low;
406  }
407  } else {
408  // acceptable voltage so reset timer
409  state[instance].low_voltage_start_ms = 0;
410  }
411 
412  // check capacity if current monitoring is enabled
413  if (has_current(instance) && (_params[instance]._low_capacity > 0) &&
414  ((_params[instance]._pack_capacity - state[instance].consumed_mah) < _params[instance]._low_capacity)) {
415  return BatteryFailsafe_Low;
416  }
417 
418  // if we've gotten this far then battery is ok
419  return BatteryFailsafe_None;
420 }
421 
422 // return true if any battery is pushing too much power
424 {
425  bool result = false;
426  for (uint8_t instance = 0; instance < _num_instances; instance++) {
427  result |= overpower_detected(instance);
428  }
429  return result;
430 }
431 
432 bool AP_BattMonitor::overpower_detected(uint8_t instance) const
433 {
434 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
435  if (instance < _num_instances && _params[instance]._watt_max > 0) {
436  float power = state[instance].current_amps * state[instance].voltage;
437  return state[instance].healthy && (power > _params[instance]._watt_max);
438  }
439  return false;
440 #else
441  return false;
442 #endif
443 }
444 
445 bool AP_BattMonitor::has_cell_voltages(const uint8_t instance) const
446 {
447  if (instance < _num_instances && drivers[instance] != nullptr) {
448  return drivers[instance]->has_cell_voltages();
449  }
450 
451  return false;
452 }
453 
454 // return the current cell voltages, returns the first monitor instances cells if the instance is out of range
455 const AP_BattMonitor::cells & AP_BattMonitor::get_cell_voltages(const uint8_t instance) const
456 {
457  if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
459  } else {
460  return state[instance].cell_voltages;
461  }
462 }
463 
464 // returns true if there is a temperature reading
465 bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance) const
466 {
467  if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
468  return false;
469  } else {
470  temperature = state[instance].temperature;
471  return (AP_HAL::millis() - state[instance].temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
472  }
473 }
474 
475 
476 namespace AP {
477 
479 {
480  return AP_BattMonitor::battery();
481 }
482 
483 };
const char * new_name
Definition: AP_Param.h:173
bool get_soft_armed() const
Definition: Util.h:15
#define AP_BATTMONITOR_SMBUS_BUS_EXTERNAL
const int8_t * _failsafe_priorities
static const struct AP_Param::GroupInfo var_info[]
void Log_Write_Current()
Definition: LogFile.cpp:1436
ap_var_type
Definition: AP_Param.h:124
#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
Definition: DataFlash.cpp:416
#define AP_BATTMONITOR_SMBUS_I2C_ADDR
static AP_BattMonitor & battery()
AP_HAL::Util * util
Definition: HAL.h:115
AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities)
GCS & gcs()
float voltage_resting_estimate() const
static const struct AP_Param::GroupInfo var_info[]
bool has_cell_voltages()
const char * result
Definition: Printf.cpp:16
const char * name
Definition: BusTest.cpp:11
#define AP_SUBGROUPINFO_FLAGS(element, name, idx, thisclazz, elclazz, flags)
Definition: AP_Param.h:110
bool overpower_detected() const
true when (voltage * current) > watt_max
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
uint32_t _log_battery_bit
float temperature
Definition: Airspeed.cpp:32
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]
Definition: AP_AHRS.cpp:486
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
battery_failsafe_handler_fn_t _battery_failsafe_handler_fn
BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES]
float voltage() const
#define f(i)
AP_Int16 _watt_max
battery pack capacity less reserve in mAh
friend class AP_BattMonitor_UAVCAN
uint32_t millis()
Definition: system.cpp:157
uint8_t _num_instances
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
float current_amps() const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
#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
Definition: HAL.h:106
#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
Definition: AP_Param.h:66
void Log_Write_Power(void)
Definition: LogFile.cpp:437
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
AP_Int8 _failsafe_low_action
capacity level used to trigger a critical battery failsafe
uint32_t old_group_element
Definition: AP_Param.h:171
virtual bool has_consumed_energy() const
returns true if battery monitor instance provides consumed energy info
enum ap_var_type type
Definition: AP_Param.h:172
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)
Definition: AP_Param.cpp:1628
bool has_current() const
virtual void init()=0
bool get_temperature(float &temperature) const
void check_failsafes(void)
friend class AP_BattMonitor_Analog
friend class AP_BattMonitor_SMBus_Maxell
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
Definition: system.cpp:140
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)
Definition: AP_Param.h:109
#define AP_BATT_MONITOR_MAX_INSTANCES
float consumed_mah() const
bool healthy() const
virtual void read()=0
#define AP_GROUPEND
Definition: AP_Param.h:121
const cells & get_cell_voltages() const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
virtual bool has_cell_voltages() const