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
uint32_t last_time_micros
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 ¶ms)
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
AP_HAL::AnalogSource * _curr_pin_analog_source
virtual void set_pin(uint8_t p)=0
AP_HAL::AnalogIn * analogin
virtual AP_HAL::AnalogSource * channel(int16_t n)=0