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/Tools/AP_Periph/batt_balance.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Periph.h"
17
18
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE
19
20
#include <dronecan_msgs.h>
21
22
extern const AP_HAL::HAL &hal;
23
24
#ifndef AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT
25
#define AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT 0
26
#endif
27
28
#ifndef AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT
29
#define AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT 1
30
#endif
31
32
#ifndef AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT
33
#define AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT 1
34
#endif
35
36
#ifndef AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT
37
#define AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT 0
38
#endif
39
40
41
const AP_Param::GroupInfo BattBalance::var_info[] {
42
// @Param: _NUM_CELLS
43
// @DisplayName: Number of battery cells
44
// @Description: Number of battery cells to monitor
45
// @Range: 0 64
46
AP_GROUPINFO("_NUM_CELLS", 1, BattBalance, num_cells, AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT),
47
48
// @Param: _ID
49
// @DisplayName: Battery ID
50
// @Description: Battery ID to match against other batteries
51
// @Range: 0 127
52
AP_GROUPINFO("_ID", 2, BattBalance, id, AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT),
53
54
// @Param: _RATE
55
// @DisplayName: Send Rate
56
// @Description: Rate to send cell information
57
// @Range: 0 20
58
AP_GROUPINFO("_RATE", 3, BattBalance, rate, AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT),
59
60
// @Param: _CELL1_PIN
61
// @DisplayName: First analog pin
62
// @Description: Analog pin of the first cell. Later cells must be sequential
63
// @Range: 0 127
64
AP_GROUPINFO("_CELL1_PIN", 4, BattBalance, cell1_pin, AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT),
65
66
AP_GROUPEND
67
};
68
69
BattBalance::BattBalance(void)
70
{
71
AP_Param::setup_object_defaults(this, var_info);
72
}
73
74
void AP_Periph_FW::batt_balance_update()
75
{
76
const int8_t ncell = battery_balance.num_cells;
77
if (ncell <= 0) {
78
return;
79
}
80
81
// allocate cell sources if needed
82
if (battery_balance.cells == nullptr) {
83
battery_balance.cells = NEW_NOTHROW AP_HAL::AnalogSource*[ncell];
84
if (battery_balance.cells == nullptr) {
85
return;
86
}
87
battery_balance.cells_allocated = ncell;
88
for (uint8_t i=0; i<battery_balance.cells_allocated; i++) {
89
battery_balance.cells[i] = hal.analogin->channel(battery_balance.cell1_pin + i);
90
}
91
}
92
93
const uint32_t now = AP_HAL::millis();
94
if (now - battery_balance.last_send_ms < 1000.0/battery_balance.rate.get()) {
95
return;
96
}
97
battery_balance.last_send_ms = now;
98
99
// allocate space for the packet. This is a large
100
// packet that won't fit on the stack, so dynamically allocate
101
auto *pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;
102
uint8_t *buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
103
if (pkt == nullptr || buffer == nullptr) {
104
delete pkt;
105
delete [] buffer;
106
return;
107
}
108
109
pkt->voltage_cell.len = battery_balance.cells_allocated;
110
float last_cell = 0;
111
for (uint8_t i=0; i<battery_balance.cells_allocated; i++) {
112
auto *chan = battery_balance.cells[i];
113
if (chan == nullptr) {
114
continue;
115
}
116
const float v = chan->voltage_average();
117
pkt->voltage_cell.data[i] = v - last_cell;
118
last_cell = v;
119
}
120
pkt->max_current = nanf("");
121
pkt->nominal_voltage = nanf("");
122
pkt->battery_id = uint8_t(battery_balance.id);
123
124
// encode and send message:
125
const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout());
126
127
canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE,
128
ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID,
129
CANARD_TRANSFER_PRIORITY_LOW,
130
buffer,
131
total_size);
132
133
delete pkt;
134
delete [] buffer;
135
}
136
137
#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE
138
139
140