9 #define AP_BATTMONITOR_SMBUS_BUS_INTERNAL 0 10 #define AP_BATTMONITOR_SMBUS_BUS_EXTERNAL 1 11 #define AP_BATTMONITOR_SMBUS_I2C_ADDR 0x0B 12 #define AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds 45 void init(
void)
override;
49 void read(
void)
override;
70 bool read_word(uint8_t reg, uint16_t& data)
const;
74 uint8_t
get_PEC(
const uint8_t i2c_addr, uint8_t cmd,
bool reading,
const uint8_t buff[], uint8_t len)
const;
84 virtual void timer(
void) = 0;
virtual void timer(void)=0
AP_BattMonitor_SMBus(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
Constructor.
uint16_t _full_charge_capacity
bool has_cell_voltages() const override
bool read_word(uint8_t reg, uint16_t &data) const
A system for managing and storing variables that are of general interest to the system.
uint8_t get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const
get_PEC - calculate packet error correction code of buffer
static AP_HAL::OwnPtr< AP_HAL::Device > dev
virtual ~AP_BattMonitor_SMBus()
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
bool read_full_charge_capacity(void)
void read(void) override
read the battery_voltage and current, should be called at 10hz
Common definitions and utility routines for the ArduPilot libraries.
bool has_current() const override
returns true if battery monitor instance provides current info
bool read_remaining_capacity(void)
bool read_serial_number(void)