APM:Libraries
AP_BattMonitor_Analog.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include <AP_Common/AP_Common.h>
3 #include <AP_Math/AP_Math.h>
4 #include "AP_BattMonitor.h"
6 
7 extern const AP_HAL::HAL& hal;
8 
12  AP_BattMonitor_Params &params) :
13  AP_BattMonitor_Backend(mon, mon_state, params)
14 {
17 
18  // always healthy
19  _state.healthy = true;
20 }
21 
22 // read - read the voltage and current
23 void
25 {
26  // this copes with changing the pin at runtime
28 
29  // get voltage
31 
32  // read current
33  if (has_current()) {
34  // calculate time since last current read
35  uint32_t tnow = AP_HAL::micros();
36  float dt = tnow - _state.last_time_micros;
37 
38  // this copes with changing the pin at runtime
40 
41  // read current
43 
44  // update total current drawn since startup
45  if (_state.last_time_micros != 0 && dt < 2000000.0f) {
46  // .0002778 is 1/3600 (conversion to hours)
47  float mah = _state.current_amps * dt * 0.0000002778f;
48  _state.consumed_mah += mah;
49  _state.consumed_wh += 0.001f * mah * _state.voltage;
50  }
51 
52  // record time
53  _state.last_time_micros = tnow;
54  }
55 }
56 
59 {
61 }
virtual float voltage_average()=0
AP_Int8 _volt_pin
0=disabled, 3=voltage only, 4=voltage and current
bool has_current() const override
returns true if battery monitor provides current info
AP_Float _volt_multiplier
board pin used to measure battery current
AP_BattMonitor_Params & _params
BattMonitor_Type type(void) const
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
AP_Float _curr_amp_per_volt
voltage on volt pin multiplied by this to calculate battery voltage
AP_Float _curr_amp_offset
voltage on current pin multiplied by this to calculate current in amps
AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params)
Constructor.
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * _volt_pin_analog_source
void read()
Read the battery voltage and current. Should be called at 10hz.
AP_BattMonitor::BattMonitor_State & _state
AP_Int8 _curr_pin
board pin used to measure battery voltage
uint32_t micros()
Definition: system.cpp:152
AP_HAL::AnalogSource * _curr_pin_analog_source
virtual void set_pin(uint8_t p)=0
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
virtual AP_HAL::AnalogSource * channel(int16_t n)=0