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