APM:Libraries
AP_BattMonitor_SMBus.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Param/AP_Param.h>
5 #include <AP_Math/AP_Math.h>
7 #include <utility>
8 
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
13 
15 {
16 public:
17 
18  // Smart Battery Data Specification Revision 1.1
20  BATTMONITOR_SMBUS_TEMP = 0x08, // Temperature
21  BATTMONITOR_SMBUS_VOLTAGE = 0x09, // Voltage
22  BATTMONITOR_SMBUS_CURRENT = 0x0A, // Current
23  BATTMONITOR_SMBUS_REMAINING_CAPACITY = 0x0F, // Remaining Capacity
24  BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY = 0x10, // Full Charge Capacity
25  BATTMONITOR_SMBUS_SPECIFICATION_INFO = 0x1A, // Specification Info
26  BATTMONITOR_SMBUS_SERIAL = 0x1C, // Serial Number
27  BATTMONITOR_SMBUS_MANUFACTURE_NAME = 0x20, // Manufacture Name
28  BATTMONITOR_SMBUS_MANUFACTURE_DATA = 0x23, // Manufacture Data
29  };
30 
34  AP_BattMonitor_Params &params,
36 
37  // virtual destructor to reduce compiler warnings
38  virtual ~AP_BattMonitor_SMBus() {}
39 
40  bool has_cell_voltages() const override { return _has_cell_voltages; }
41 
42  // all smart batteries are expected to provide current
43  bool has_current() const override { return true; }
44 
45  void init(void) override;
46 
47 protected:
48 
49  void read(void) override;
50 
51  // reads the pack full charge capacity
52  // returns true if the read was successful, or if we already knew the pack capacity
53  bool read_full_charge_capacity(void);
54 
55  // reads the remaining capacity
56  // returns true if the read was succesful, which is only considered to be the
57  // we know the full charge capacity
58  bool read_remaining_capacity(void);
59 
60  // reads the temperature word from the battery
61  // returns true if the read was successful
62  bool read_temp(void);
63 
64  // reads the serial number if it's not already known
65  // returns true if the read was successful, or the number was already known
66  bool read_serial_number(void);
67 
68  // read word from register
69  // returns true if read was successful, false if failed
70  bool read_word(uint8_t reg, uint16_t& data) const;
71 
72  // get_PEC - calculate PEC for a read or write from the battery
73  // buff is the data that was read or will be written
74  uint8_t get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
75 
77  bool _pec_supported; // true if PEC is supported
78 
79  int32_t _serial_number = -1; // battery serial number
80  uint16_t _full_charge_capacity; // full charge capacity, used to stash the value before setting the parameter
81 
82  bool _has_cell_voltages; // smbus backends flag this as true once they have recieved a valid cell voltage report
83 
84  virtual void timer(void) = 0; // timer function to read from the battery
85 
86 };
87 
88 // include specific implementations
virtual void timer(void)=0
AP_BattMonitor_SMBus(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
Constructor.
bool has_cell_voltages() const override
bool read_word(uint8_t reg, uint16_t &data) const
void init(void) override
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
Definition: ICM20789.cpp:16
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
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