APM:Libraries
AP_BattMonitor_SMBus_Maxell.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_BattMonitor.h"
6 #include <utility>
7 
8 #define BATTMONITOR_SMBUS_MAXELL_NUM_CELLS 6
9 uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
10  0x3e, // cell 2
11  0x3d, // cell 3
12  0x3c, // cell 4
13  0x3b, // cell 5
14  0x3a}; // cell 6
15 
16 #define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes.
17 
18 /*
19  * Other potentially useful registers, listed here for future use
20  * #define BATTMONITOR_SMBUS_MAXELL_CHARGE_STATUS 0x0d // relative state of charge
21  * #define BATTMONITOR_SMBUS_MAXELL_BATTERY_STATUS 0x16 // battery status register including alarms
22  * #define BATTMONITOR_SMBUS_MAXELL_BATTERY_CYCLE_COUNT 0x17 // cycle count
23  * #define BATTMONITOR_SMBUS_MAXELL_DESIGN_VOLTAGE 0x19 // design voltage register
24  * #define BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_DATE 0x1b // manufacturer date
25  * #define BATTMONITOR_SMBUS_MAXELL_SERIALNUM 0x1c // serial number register
26  * #define BATTMONITOR_SMBUS_MAXELL_HEALTH_STATUS 0x4f // state of health
27  * #define BATTMONITOR_SMBUS_MAXELL_SAFETY_ALERT 0x50 // safety alert
28  * #define BATTMONITOR_SMBUS_MAXELL_SAFETY_STATUS 0x50 // safety status
29  * #define BATTMONITOR_SMBUS_MAXELL_PF_ALERT 0x52 // safety status
30  * #define BATTMONITOR_SMBUS_MAXELL_PF_STATUS 0x53 // safety status
31 */
32 
33 // Constructor
36  AP_BattMonitor_Params &params,
38  : AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
39 {}
40 
42 {
43  // check if PEC is supported
44  if (!check_pec_support()) {
45  return;
46  }
47 
48  uint16_t data;
49  uint32_t tnow = AP_HAL::micros();
50 
51  // read voltage (V)
53  _state.voltage = (float)data / 1000.0f;
54  _state.last_time_micros = tnow;
55  _state.healthy = true;
56  }
57 
58  // read cell voltages
59  for (uint8_t i = 0; i < BATTMONITOR_SMBUS_MAXELL_NUM_CELLS; i++) {
60  if (read_word(maxell_cell_ids[i], data)) {
61  _has_cell_voltages = true;
62  _state.cell_voltages.cells[i] = data;
63  } else {
64  _state.cell_voltages.cells[i] = UINT16_MAX;
65  }
66  }
67 
68  // timeout after 5 seconds
70  _state.healthy = false;
71  return;
72  }
73 
74  // read current (A)
76  _state.current_amps = -(float)((int16_t)data) / 1000.0f;
77  _state.last_time_micros = tnow;
78  }
79 
81 
82  // FIXME: Preform current integration if the remaining capacity can't be requested
84 
85  read_temp();
86 
88 }
89 
90 // read_block - returns number of characters read if successful, zero if unsuccessful
91 uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool append_zero) const
92 {
93  // get length
94  uint8_t bufflen;
95  // read byte (first byte indicates the number of bytes in the block)
96  if (!_dev->read_registers(reg, &bufflen, 1)) {
97  return 0;
98  }
99 
100  // sanity check length returned by smbus
101  if (bufflen == 0 || bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER) {
102  return 0;
103  }
104 
105  // buffer to hold results (2 extra byte returned holding length and PEC)
106  const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0);
107  uint8_t buff[read_size];
108 
109  // read bytes
110  if (!_dev->read_registers(reg, buff, read_size)) {
111  return 0;
112  }
113 
114  // check PEC
115  if (_pec_supported) {
116  uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
117  if (pec != buff[bufflen+1]) {
118  return 0;
119  }
120  }
121 
122  // copy data (excluding PEC)
123  memcpy(data, &buff[1], bufflen);
124 
125  // optionally add zero to end
126  if (append_zero) {
127  data[bufflen] = '\0';
128  }
129 
130  // return success
131  return bufflen;
132 }
133 
134 // check if PEC supported with the version value in SpecificationInfo() function
135 // returns true once PEC is confirmed as working or not working
137 {
138  // exit immediately if we have already confirmed pec support
139  if (_pec_confirmed) {
140  return true;
141  }
142 
143  // specification info
144  uint16_t data;
146  return false;
147  }
148 
149  // extract version
150  uint8_t version = (data & 0xF0) >> 4;
151 
152  // version less than 0011b (i.e. 3) do not support PEC
153  if (version < 3) {
154  _pec_supported = false;
155  _pec_confirmed = true;
156  return true;
157  }
158 
159  // check manufacturer name
160  uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1];
162  // Hitachi maxell batteries do not support PEC
163  if (strcmp((char*)buff, "Hitachi maxell") == 0) {
164  _pec_supported = false;
165  _pec_confirmed = true;
166  return true;
167  }
168  }
169 
170  // assume all other batteries support PEC
171  _pec_supported = true;
172  _pec_confirmed = true;
173  return true;
174 }
175 
#define AP_BATTMONITOR_SMBUS_I2C_ADDR
#define BATTMONITOR_SMBUS_MAXELL_NUM_CELLS
#define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER
bool read_word(uint8_t reg, uint16_t &data) const
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
uint8_t maxell_cell_ids[]
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
#define f(i)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
uint8_t read_block(uint8_t reg, uint8_t *data, bool append_zero) const
Common definitions and utility routines for the ArduPilot libraries.
#define AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS
AP_BattMonitor::BattMonitor_State & _state
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
AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)