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_LTC2946.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_LTC2946_ENABLED
4
5
#include <GCS_MAVLink/GCS.h>
6
#include <AP_HAL/utility/sparse-endian.h>
7
8
#include "AP_BattMonitor_LTC2946.h"
9
10
extern const AP_HAL::HAL& hal;
11
12
#define REG_CTRLA 0x00
13
#define REG_CTRLB 0x01
14
#define REG_STATUS 0x80
15
#define REG_MFR_ID 0xe7
16
17
// first byte of 16 bit ID is stable
18
#define ID_LTC2946 0x60
19
20
#define REG_DELTA 0x14 // 16 bits
21
#define REG_VIN 0x1e // 16 bits
22
23
#define REGA_CONF 0x18 // sense, alternate
24
#define REGB_CONF 0x01 // auto-reset
25
26
void AP_BattMonitor_LTC2946::init(void)
27
{
28
dev = hal.i2c_mgr->get_device(HAL_BATTMON_LTC2946_BUS, HAL_BATTMON_LTC2946_ADDR, 100000, false, 20);
29
if (!dev) {
30
return;
31
}
32
33
uint8_t id = 0;
34
WITH_SEMAPHORE(dev->get_semaphore());
35
if (!dev->read_registers(REG_MFR_ID, &id, 1) || id != ID_LTC2946) {
36
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: Failed to find device 0x%04x", unsigned(id));
37
return;
38
}
39
40
if (!dev->write_register(REG_CTRLA, REGA_CONF) ||
41
!dev->write_register(REG_CTRLB, REGB_CONF)) {
42
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: Failed to configure device");
43
return;
44
}
45
46
// use datasheet typical values
47
voltage_LSB = 102.4 / 4095.0;
48
current_LSB = (0.1024/0.0005) / 4095.0;
49
50
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: found monitor on bus %u", HAL_BATTMON_LTC2946_BUS);
51
52
if (dev) {
53
dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_LTC2946::timer, void));
54
}
55
}
56
57
/// read the battery_voltage and current, should be called at 10hz
58
void AP_BattMonitor_LTC2946::read(void)
59
{
60
WITH_SEMAPHORE(accumulate.sem);
61
_state.healthy = accumulate.count > 0;
62
if (!_state.healthy) {
63
return;
64
}
65
66
_state.voltage = accumulate.volt_sum / accumulate.count;
67
_state.current_amps = accumulate.current_sum / accumulate.count;
68
accumulate.volt_sum = 0;
69
accumulate.current_sum = 0;
70
accumulate.count = 0;
71
72
const uint32_t tnow = AP_HAL::micros();
73
const uint32_t dt_us = tnow - _state.last_time_micros;
74
75
// update total current drawn since startup
76
update_consumed(_state, dt_us);
77
78
_state.last_time_micros = tnow;
79
}
80
81
/*
82
read word from register
83
returns true if read was successful, false if failed
84
*/
85
bool AP_BattMonitor_LTC2946::read_word(const uint8_t reg, uint16_t& data) const
86
{
87
// read the appropriate register from the device
88
if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {
89
return false;
90
}
91
92
// convert byte order
93
data = uint16_t(be16toh(uint16_t(data)));
94
95
// return success
96
return true;
97
}
98
99
void AP_BattMonitor_LTC2946::timer(void)
100
{
101
uint16_t amps, volts;
102
if (!read_word(REG_DELTA, amps) ||
103
!read_word(REG_VIN, volts)) {
104
return;
105
}
106
WITH_SEMAPHORE(accumulate.sem);
107
// convert 12 bit ADC data
108
accumulate.volt_sum += (volts>>4) * voltage_LSB;
109
accumulate.current_sum += (amps>>4) * current_LSB;
110
accumulate.count++;
111
}
112
113
#endif // AP_BATTERY_LTC2946_ENABLED
114
115