APM:Libraries
AP_BattMonitor_SMBus_Solo.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_Notify/AP_Notify.h>
5 #include "AP_BattMonitor.h"
7 #include <utility>
8 
9 #define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register
10 #define BATTMONITOR_SMBUS_SOLO_CURRENT 0x2a // current register
11 #define BATTMONITOR_SMBUS_SOLO_BUTTON_DEBOUNCE 3 // button held down for 3 intervals will cause a power off event
12 
13 #define BATTMONITOR_SMBUS_SOLO_NUM_CELLS 4
14 
15 /*
16  * Other potentially useful registers, listed here for future use
17  * #define BATTMONITOR_SMBUS_SOLO_VOLTAGE 0x09 // voltage register
18  * #define BATTMONITOR_SMBUS_SOLO_BATTERY_STATUS 0x16 // battery status register including alarms
19  * #define BATTMONITOR_SMBUS_SOLO_DESIGN_CAPACITY 0x18 // design capacity register
20  * #define BATTMONITOR_SMBUS_SOLO_DESIGN_VOLTAGE 0x19 // design voltage register
21  * #define BATTMONITOR_SMBUS_SOLO_SERIALNUM 0x1c // serial number register
22  * #define BATTMONITOR_SMBUS_SOLO_MANUFACTURE_NAME 0x20 // manufacturer name
23  * #define BATTMONITOR_SMBUS_SOLO_DEVICE_NAME 0x21 // device name
24  * #define BATTMONITOR_SMBUS_SOLO_DEVICE_CHEMISTRY 0x22 // device chemistry
25  * #define BATTMONITOR_SMBUS_SOLO_MANUFACTURE_INFO 0x25 // manufacturer info including cell voltage
26  */
27 
28 // Constructor
31  AP_BattMonitor_Params &params,
33  : AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
34 {
35  _pec_supported = true;
36 }
37 
39 {
40  uint8_t buff[8];
41  uint32_t tnow = AP_HAL::micros();
42 
43 
44  // read cell voltages
45  if (read_block(BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE, buff, 8, false)) {
46  float pack_voltage_mv = 0.0f;
47  for (uint8_t i = 0; i < BATTMONITOR_SMBUS_SOLO_NUM_CELLS; i++) {
48  uint16_t cell = buff[(i * 2) + 1] << 8 | buff[i * 2];
49  _state.cell_voltages.cells[i] = cell;
50  pack_voltage_mv += (float)cell;
51  }
52  _has_cell_voltages = true;
53 
54  // accumulate the pack voltage out of the total of the cells
55  // because the Solo's I2C bus is so noisy, it's worth not spending the
56  // time and bus bandwidth to request the pack voltage as a seperate
57  // transaction
58  _state.voltage = pack_voltage_mv * 1e-3;
59  _state.last_time_micros = tnow;
60  _state.healthy = true;
61  }
62 
63  // timeout after 5 seconds
65  _state.healthy = false;
66  // do not attempt to ready any more data from battery
67  return;
68  }
69 
70  // read current
71  if (read_block(BATTMONITOR_SMBUS_SOLO_CURRENT, buff, 4, false) == 4) {
72  _state.current_amps = -(float)((int32_t)((uint32_t)buff[3]<<24 | (uint32_t)buff[2]<<16 | (uint32_t)buff[1]<<8 | (uint32_t)buff[0])) / 1000.0f;
73  _state.last_time_micros = tnow;
74  }
75 
78 
79  // read the button press indicator
80  if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_DATA, buff, 6, false) == 6) {
81  bool pressed = (buff[1] >> 3) & 0x01;
82 
84  // battery will power off
86  } else if (pressed) {
87  // battery will power off if the button is held
89 
90  } else {
91  // button released, reset counters
94  }
95  }
96 
97  read_temp();
98 
100 }
101 
102 // read_block - returns number of characters read if successful, zero if unsuccessful
103 uint8_t AP_BattMonitor_SMBus_Solo::read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero) const
104 {
105  uint8_t buff[max_len+2]; // buffer to hold results (2 extra byte returned holding length and PEC)
106 
107  // read bytes
108  if (!_dev->read_registers(reg, buff, sizeof(buff))) {
109  return 0;
110  }
111 
112  // get length
113  uint8_t bufflen = buff[0];
114 
115  // sanity check length returned by smbus
116  if (bufflen == 0 || bufflen > max_len) {
117  return 0;
118  }
119 
120  // check PEC
121  uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
122  if (pec != buff[bufflen+1]) {
123  return 0;
124  }
125 
126  // copy data (excluding PEC)
127  memcpy(data, &buff[1], bufflen);
128 
129  // optionally add zero to end
130  if (append_zero) {
131  data[bufflen] = '\0';
132  }
133 
134  // return success
135  return bufflen;
136 }
137 
#define BATTMONITOR_SMBUS_SOLO_BUTTON_DEBOUNCE
AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
#define BATTMONITOR_SMBUS_SOLO_NUM_CELLS
#define AP_BATTMONITOR_SMBUS_I2C_ADDR
uint8_t read_block(uint8_t reg, uint8_t *data, uint8_t max_len, bool append_zero) const
#define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
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
Common definitions and utility routines for the ArduPilot libraries.
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
#define AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS
AP_BattMonitor::BattMonitor_State & _state
#define BATTMONITOR_SMBUS_SOLO_CURRENT
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
uint32_t micros()
Definition: system.cpp:152