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_INA239.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_INA239_ENABLED
4
5
#include <GCS_MAVLink/GCS.h>
6
#include <AP_HAL/utility/sparse-endian.h>
7
8
#include "AP_BattMonitor_INA239.h"
9
10
extern const AP_HAL::HAL& hal;
11
12
/*
13
note that registers are clocked on SPI MSB first, with register
14
number in top 6 bits, LSB is read flag
15
*/
16
#define REG_CONFIG 0x00
17
#define REG_ADC_CONFIG 0x01
18
#define REG_SHUNT_CAL 0x02
19
#define REG_SHUNT_VOLTAGE 0x04
20
#define REG_BUS_VOLTAGE 0x05
21
#define REG_CURRENT 0x07
22
23
#define REG_ADC_CONFIG_RESET 0xFB68U
24
25
#ifndef HAL_BATTMON_INA239_SHUNT_RESISTANCE
26
#define HAL_BATTMON_INA239_SHUNT_RESISTANCE 0.0002
27
#endif
28
29
#ifndef HAL_BATTMON_INA239_MAX_CURRENT
30
#define HAL_BATTMON_INA239_MAX_CURRENT 90
31
#endif
32
33
const AP_Param::GroupInfo AP_BattMonitor_INA239::var_info[] = {
34
35
// @Param: MAX_AMPS
36
// @DisplayName: Battery monitor max current
37
// @Description: This controls the maximum current the INA239 sensor will work with.
38
// @Range: 1 400
39
// @Units: A
40
// @User: Advanced
41
AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA239, max_amps, HAL_BATTMON_INA239_MAX_CURRENT),
42
43
// @Param: SHUNT
44
// @DisplayName: Battery monitor shunt resistor
45
// @Description: This sets the shunt resistor used in the device
46
// @Range: 0.0001 0.01
47
// @Units: Ohm
48
// @User: Advanced
49
AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA239, rShunt, HAL_BATTMON_INA239_SHUNT_RESISTANCE),
50
51
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
52
53
AP_GROUPEND
54
};
55
56
AP_BattMonitor_INA239::AP_BattMonitor_INA239(AP_BattMonitor &mon,
57
AP_BattMonitor::BattMonitor_State &mon_state,
58
AP_BattMonitor_Params &params)
59
: AP_BattMonitor_Backend(mon, mon_state, params)
60
{
61
AP_Param::setup_object_defaults(this, var_info);
62
_state.var_info = var_info;
63
}
64
65
void AP_BattMonitor_INA239::init(void)
66
{
67
dev = hal.spi->get_device(AP_BATTERY_INA239_SPI_DEVICE);
68
if (!dev) {
69
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "device fail");
70
return;
71
}
72
dev->set_read_flag(0x01);
73
// register now and configure in the timer callbacks
74
dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA239::timer, void));
75
}
76
77
void AP_BattMonitor_INA239::configure(void)
78
{
79
WITH_SEMAPHORE(dev->get_semaphore());
80
81
int16_t adc_config = 0;
82
83
if (!read_word(REG_ADC_CONFIG, adc_config) ||
84
uint16_t(adc_config) != REG_ADC_CONFIG_RESET) {
85
return;
86
}
87
88
voltage_LSB = 3.125e-3;
89
current_LSB = max_amps.get() / 0x8000;
90
const int16_t shunt_cal = 819.2 * 1e6 * current_LSB * rShunt.get();
91
int16_t shunt_cal2 = 0;
92
93
if (!write_word(REG_SHUNT_CAL, shunt_cal) ||
94
!read_word(REG_SHUNT_CAL, shunt_cal2) ||
95
shunt_cal != shunt_cal2) {
96
return;
97
}
98
99
configured = true;
100
}
101
102
/// read the battery_voltage and current, should be called at 10hz
103
void AP_BattMonitor_INA239::read(void)
104
{
105
WITH_SEMAPHORE(accumulate.sem);
106
_state.healthy = accumulate.count > 0;
107
if (!_state.healthy) {
108
return;
109
}
110
111
_state.voltage = accumulate.volt_sum / accumulate.count;
112
_state.current_amps = accumulate.current_sum / accumulate.count;
113
accumulate.volt_sum = 0;
114
accumulate.current_sum = 0;
115
accumulate.count = 0;
116
117
const uint32_t tnow = AP_HAL::micros();
118
const uint32_t dt_us = tnow - _state.last_time_micros;
119
120
// update total current drawn since startup
121
update_consumed(_state, dt_us);
122
123
_state.last_time_micros = tnow;
124
}
125
126
/*
127
read word from register
128
returns true if read was successful, false if failed
129
*/
130
bool AP_BattMonitor_INA239::read_word(const uint8_t reg, int16_t& data) const
131
{
132
// read the appropriate register from the device
133
if (!dev->read_registers(reg<<2, (uint8_t *)&data, sizeof(data))) {
134
return false;
135
}
136
137
// convert byte order
138
data = int16_t(be16toh(uint16_t(data)));
139
140
return true;
141
}
142
143
/*
144
write word to a register, byte swapped
145
returns true if write was successful, false if failed
146
*/
147
bool AP_BattMonitor_INA239::write_word(const uint8_t reg, const uint16_t data) const
148
{
149
const uint8_t b[3] { uint8_t(reg<<2), uint8_t(data >> 8), uint8_t(data&0xff) };
150
return dev->transfer(b, sizeof(b), nullptr, 0);
151
}
152
153
void AP_BattMonitor_INA239::timer(void)
154
{
155
// allow for power-on after boot
156
if (!configured) {
157
uint32_t now = AP_HAL::millis();
158
if (now - last_configure_ms > 200) {
159
// try contacting the device at 5Hz
160
last_configure_ms = now;
161
configure();
162
}
163
if (!configured) {
164
// waiting for the device to respond
165
return;
166
}
167
}
168
169
int16_t bus_voltage, current;
170
171
if (!read_word(REG_BUS_VOLTAGE, bus_voltage) ||
172
!read_word(REG_CURRENT, current)) {
173
failed_reads++;
174
if (failed_reads > 10) {
175
// device has disconnected, we need to reconfigure it
176
configured = false;
177
}
178
return;
179
}
180
failed_reads = 0;
181
182
WITH_SEMAPHORE(accumulate.sem);
183
accumulate.volt_sum += bus_voltage * voltage_LSB;
184
accumulate.current_sum += current * current_LSB;
185
accumulate.count++;
186
}
187
188
#endif // AP_BATTERY_INA239_ENABLED
189
190