CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_INA2XX_ENABLED
4
5
/*
6
supports INA226, INA228 and INA238 I2C battery monitors
7
*/
8
9
#include <AP_HAL/utility/sparse-endian.h>
10
11
#include "AP_BattMonitor_INA2xx.h"
12
13
extern const AP_HAL::HAL& hal;
14
15
16
// INA226 specific registers
17
#define REG_226_CONFIG 0x00
18
#define REG_226_CONFIG_DEFAULT 0x4127
19
#define REG_226_CONFIG_RESET 0x8000
20
#define REG_226_BUS_VOLTAGE 0x02
21
#define REG_226_CURRENT 0x04
22
#define REG_226_CALIBRATION 0x05
23
#define REG_226_MANUFACT_ID 0xfe
24
25
// INA228 specific registers
26
#define REG_228_CONFIG 0x00
27
#define REG_228_CONFIG_RESET 0x8000
28
#define REG_228_ADC_CONFIG 0x01
29
#define REG_228_SHUNT_CAL 0x02
30
#define REG_228_VBUS 0x05
31
#define REG_228_CURRENT 0x07
32
#define REG_228_MANUFACT_ID 0x3e
33
#define REG_228_DEVICE_ID 0x3f
34
#define REG_228_DIETEMP 0x06
35
#define INA_228_TEMP_C_LSB 7.8125e-3
36
37
// INA237/INA238 specific registers
38
#define REG_238_CONFIG 0x00
39
#define REG_238_CONFIG_RESET 0x8000
40
#define REG_238_ADC_CONFIG 0x01
41
#define REG_238_SHUNT_CAL 0x02
42
#define REG_238_VBUS 0x05
43
#define REG_238_CURRENT 0x07
44
#define REG_238_MANUFACT_ID 0x3e
45
#define REG_238_DEVICE_ID 0x3f
46
#define REG_238_DIETEMP 0x06
47
#define INA_238_TEMP_C_LSB 7.8125e-3 // need to mask bottom 4 bits
48
49
// INA231 specific registers
50
#define REG_231_CONFIG 0x00
51
#define REG_231_SHUNT_VOLTAGE 0x01
52
#define REG_231_BUS_VOLTAGE 0x02
53
#define REG_231_POWER 0x03
54
#define REG_231_CURRENT 0x04
55
#define REG_231_CALIBRATION 0x05
56
#define REG_231_MASK 0x06
57
#define REG_231_ALERT 0x07
58
59
60
#ifndef DEFAULT_BATTMON_INA2XX_MAX_AMPS
61
#define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.0
62
#endif
63
64
#ifndef DEFAULT_BATTMON_INA2XX_SHUNT
65
#define DEFAULT_BATTMON_INA2XX_SHUNT 0.0005
66
#endif
67
68
#ifndef HAL_BATTMON_INA2XX_BUS
69
#define HAL_BATTMON_INA2XX_BUS 0
70
#endif
71
#ifndef HAL_BATTMON_INA2XX_ADDR
72
#define HAL_BATTMON_INA2XX_ADDR 0
73
#endif
74
75
// list of addresses to probe if I2C_ADDR is zero
76
const uint8_t AP_BattMonitor_INA2XX::i2c_probe_addresses[] { 0x41, 0x44, 0x45 };
77
78
const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {
79
80
// @Param: I2C_BUS
81
// @DisplayName: Battery monitor I2C bus number
82
// @Description: Battery monitor I2C bus number
83
// @Range: 0 3
84
// @User: Advanced
85
// @RebootRequired: True
86
AP_GROUPINFO("I2C_BUS", 25, AP_BattMonitor_INA2XX, i2c_bus, HAL_BATTMON_INA2XX_BUS),
87
88
// @Param: I2C_ADDR
89
// @DisplayName: Battery monitor I2C address
90
// @Description: Battery monitor I2C address. If this is zero then probe list of supported addresses
91
// @Range: 0 127
92
// @User: Advanced
93
// @RebootRequired: True
94
AP_GROUPINFO("I2C_ADDR", 26, AP_BattMonitor_INA2XX, i2c_address, HAL_BATTMON_INA2XX_ADDR),
95
96
// @Param: MAX_AMPS
97
// @DisplayName: Battery monitor max current
98
// @Description: This controls the maximum current the INS2XX sensor will work with.
99
// @Range: 1 400
100
// @Units: A
101
// @User: Advanced
102
AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA2XX, max_amps, DEFAULT_BATTMON_INA2XX_MAX_AMPS),
103
104
// @Param: SHUNT
105
// @DisplayName: Battery monitor shunt resistor
106
// @Description: This sets the shunt resistor used in the device
107
// @Range: 0.0001 0.01
108
// @Units: Ohm
109
// @User: Advanced
110
AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT),
111
112
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
113
114
AP_GROUPEND
115
};
116
117
AP_BattMonitor_INA2XX::AP_BattMonitor_INA2XX(AP_BattMonitor &mon,
118
AP_BattMonitor::BattMonitor_State &mon_state,
119
AP_BattMonitor_Params &params)
120
: AP_BattMonitor_Backend(mon, mon_state, params)
121
{
122
AP_Param::setup_object_defaults(this, var_info);
123
_state.var_info = var_info;
124
}
125
126
void AP_BattMonitor_INA2XX::init(void)
127
{
128
dev = hal.i2c_mgr->get_device(i2c_bus, i2c_address, 100000, false, 20);
129
if (!dev) {
130
return;
131
}
132
// register now and configure in the timer callbacks
133
dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void));
134
}
135
136
bool AP_BattMonitor_INA2XX::configure(DevType dtype)
137
{
138
switch (dtype) {
139
case DevType::UNKNOWN:
140
return false;
141
142
case DevType::INA226: {
143
// configure for MAX_AMPS
144
const uint16_t conf = (0x2<<9) | (0x5<<6) | (0x5<<3) | 0x7; // 2ms conv time, 16x sampling
145
current_LSB = max_amps / 32768.0;
146
voltage_LSB = 0.00125; // 1.25mV/bit
147
const uint16_t cal = uint16_t(0.00512 / (current_LSB * rShunt));
148
if (write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) && // reset
149
write_word(REG_226_CONFIG, conf) &&
150
write_word(REG_226_CALIBRATION, cal)) {
151
dev_type = dtype;
152
return true;
153
}
154
break;
155
}
156
157
case DevType::INA228: {
158
// configure for MAX_AMPS
159
voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB
160
current_LSB = max_amps / (1U<<19);
161
const uint16_t shunt_cal = uint16_t(13107.2e6 * current_LSB * rShunt) & 0x7FFF;
162
if (write_word(REG_228_CONFIG, REG_228_CONFIG_RESET) && // reset
163
write_word(REG_228_CONFIG, 0) &&
164
write_word(REG_228_SHUNT_CAL, shunt_cal)) {
165
dev_type = dtype;
166
return true;
167
}
168
break;
169
}
170
171
case DevType::INA238: {
172
// configure for MAX_AMPS
173
voltage_LSB = 3.125e-3; // 3.125mV/LSB
174
current_LSB = max_amps / (1U<<15);
175
const uint16_t shunt_cal = uint16_t(819.2e6 * current_LSB * rShunt) & 0x7FFF;
176
if (write_word(REG_238_CONFIG, REG_238_CONFIG_RESET) && // reset
177
write_word(REG_238_CONFIG, 0) &&
178
write_word(REG_238_SHUNT_CAL, shunt_cal)) {
179
dev_type = dtype;
180
return true;
181
}
182
break;
183
}
184
185
case DevType::INA231: {
186
// no configuration needed
187
voltage_LSB = 1.25e-3;
188
current_LSB = max_amps / (1U<<15);
189
const uint16_t cal = 0.00512 / (current_LSB * rShunt);
190
if (write_word(REG_231_CALIBRATION, cal)) {
191
return true;
192
}
193
}
194
195
}
196
return false;
197
}
198
199
/// read the battery_voltage and current, should be called at 10hz
200
void AP_BattMonitor_INA2XX::read(void)
201
{
202
WITH_SEMAPHORE(accumulate.sem);
203
_state.healthy = accumulate.count > 0;
204
if (!_state.healthy) {
205
return;
206
}
207
208
_state.voltage = accumulate.volt_sum / accumulate.count;
209
_state.current_amps = accumulate.current_sum / accumulate.count;
210
accumulate.volt_sum = 0;
211
accumulate.current_sum = 0;
212
accumulate.count = 0;
213
214
const uint32_t tnow = AP_HAL::micros();
215
const uint32_t dt_us = tnow - _state.last_time_micros;
216
217
// update total current drawn since startup
218
update_consumed(_state, dt_us);
219
220
_state.last_time_micros = tnow;
221
}
222
223
/*
224
read 16 bit word from register
225
returns true if read was successful, false if failed
226
*/
227
bool AP_BattMonitor_INA2XX::read_word16(const uint8_t reg, int16_t& data) const
228
{
229
// read the appropriate register from the device
230
if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {
231
return false;
232
}
233
234
// convert byte order
235
data = int16_t(be16toh(uint16_t(data)));
236
237
return true;
238
}
239
240
/*
241
read 24 bit signed value from register
242
returns true if read was successful, false if failed
243
*/
244
bool AP_BattMonitor_INA2XX::read_word24(const uint8_t reg, int32_t& data) const
245
{
246
// read the appropriate register from the device
247
uint8_t d[3];
248
if (!dev->read_registers(reg, d, sizeof(d))) {
249
return false;
250
}
251
// 24 bit 2s complement data. Shift into upper 24 bits of int32_t then divide by 256
252
// to cope with negative numbers properly
253
data = d[0]<<24 | d[1]<<16 | d[2] << 8;
254
data = data / 256;
255
256
return true;
257
}
258
259
/*
260
write word to a register, byte swapped
261
returns true if write was successful, false if failed
262
*/
263
bool AP_BattMonitor_INA2XX::write_word(const uint8_t reg, const uint16_t data) const
264
{
265
const uint8_t b[3] { reg, uint8_t(data >> 8), uint8_t(data&0xff) };
266
return dev->transfer(b, sizeof(b), nullptr, 0);
267
}
268
269
/*
270
detect device type. This may happen well after power on if battery is
271
not plugged in yet
272
*/
273
bool AP_BattMonitor_INA2XX::detect_device(void)
274
{
275
uint32_t now = AP_HAL::millis();
276
if (now - last_detect_ms < 200) {
277
// don't flood the bus
278
return false;
279
}
280
last_detect_ms = now;
281
int16_t id;
282
283
WITH_SEMAPHORE(dev->get_semaphore());
284
285
if (i2c_address.get() == 0) {
286
dev->set_address(i2c_probe_addresses[i2c_probe_next]);
287
i2c_probe_next = (i2c_probe_next+1) % sizeof(i2c_probe_addresses);
288
}
289
290
if (read_word16(REG_228_MANUFACT_ID, id) && id == 0x5449 &&
291
read_word16(REG_228_DEVICE_ID, id) && (id&0xFFF0) == 0x2280) {
292
has_temp = true;
293
return configure(DevType::INA228);
294
}
295
if (read_word16(REG_238_MANUFACT_ID, id) && id == 0x5449 &&
296
read_word16(REG_238_DEVICE_ID, id) && (id&0xFFF0) == 0x2380) {
297
has_temp = true;
298
return configure(DevType::INA238);
299
}
300
if (read_word16(REG_226_MANUFACT_ID, id) && id == 0x5449 &&
301
write_word(REG_226_CONFIG, REG_226_CONFIG_RESET) &&
302
write_word(REG_226_CONFIG, REG_226_CONFIG_DEFAULT) &&
303
read_word16(REG_226_CONFIG, id) &&
304
id == REG_226_CONFIG_DEFAULT) {
305
return configure(DevType::INA226);
306
}
307
if (read_word16(REG_231_CONFIG, id) && id == 0x4127) {
308
// no manufacturer ID for 231
309
return configure(DevType::INA231);
310
}
311
312
return false;
313
}
314
315
316
void AP_BattMonitor_INA2XX::timer(void)
317
{
318
if (dev_type == DevType::UNKNOWN) {
319
if (!detect_device()) {
320
return;
321
}
322
}
323
324
float voltage = 0, current = 0;
325
326
switch (dev_type) {
327
case DevType::UNKNOWN:
328
return;
329
330
case DevType::INA226: {
331
int16_t bus_voltage16, current16;
332
if (!read_word16(REG_226_BUS_VOLTAGE, bus_voltage16) ||
333
!read_word16(REG_226_CURRENT, current16)) {
334
failed_reads++;
335
if (failed_reads > 10) {
336
// device has disconnected, we need to reconfigure it
337
dev_type = DevType::UNKNOWN;
338
}
339
return;
340
}
341
voltage = bus_voltage16 * voltage_LSB;
342
current = current16 * current_LSB;
343
break;
344
}
345
346
case DevType::INA228: {
347
int32_t bus_voltage24, current24;
348
int16_t temp16;
349
if (!read_word24(REG_228_VBUS, bus_voltage24) ||
350
!read_word24(REG_228_CURRENT, current24) ||
351
!read_word16(REG_228_DIETEMP, temp16)) {
352
failed_reads++;
353
if (failed_reads > 10) {
354
// device has disconnected, we need to reconfigure it
355
dev_type = DevType::UNKNOWN;
356
}
357
return;
358
}
359
voltage = (bus_voltage24>>4) * voltage_LSB;
360
current = (current24>>4) * current_LSB;
361
temperature = temp16 * INA_228_TEMP_C_LSB;
362
break;
363
}
364
365
case DevType::INA238: {
366
int16_t bus_voltage16, current16, temp16;
367
if (!read_word16(REG_238_VBUS, bus_voltage16) ||
368
!read_word16(REG_238_CURRENT, current16) ||
369
!read_word16(REG_238_DIETEMP, temp16)) {
370
failed_reads++;
371
if (failed_reads > 10) {
372
// device has disconnected, we need to reconfigure it
373
dev_type = DevType::UNKNOWN;
374
}
375
return;
376
}
377
voltage = bus_voltage16 * voltage_LSB;
378
current = current16 * current_LSB;
379
temperature = (temp16&0xFFF0) * INA_238_TEMP_C_LSB;
380
break;
381
}
382
383
case DevType::INA231: {
384
int16_t bus_voltage16, current16;
385
if (!read_word16(REG_231_SHUNT_VOLTAGE, bus_voltage16) ||
386
!read_word16(REG_231_CURRENT, current16)) {
387
failed_reads++;
388
if (failed_reads > 10) {
389
// device has disconnected, we need to reconfigure it
390
dev_type = DevType::UNKNOWN;
391
}
392
return;
393
}
394
voltage = bus_voltage16 * voltage_LSB;
395
current = current16 * current_LSB;
396
break;
397
}
398
}
399
400
failed_reads = 0;
401
402
WITH_SEMAPHORE(accumulate.sem);
403
accumulate.volt_sum += voltage;
404
accumulate.current_sum += current;
405
accumulate.count++;
406
}
407
408
/*
409
get last temperature
410
*/
411
bool AP_BattMonitor_INA2XX::get_temperature(float &temp) const
412
{
413
temp = temperature;
414
return has_temp;
415
}
416
417
#endif // AP_BATTERY_INA2XX_ENABLED
418
419