21 void timer(
void)
override;
24 uint8_t
read_block(uint8_t reg, uint8_t* data, uint8_t max_len,
bool append_zero)
const;
AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
uint8_t read_block(uint8_t reg, uint8_t *data, uint8_t max_len, bool append_zero) const
A system for managing and storing variables that are of general interest to the system.
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Common definitions and utility routines for the ArduPilot libraries.
uint8_t _button_press_count
void timer(void) override