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_DroneCAN.cpp
Views: 1798
1
#include "AP_BattMonitor_config.h"
2
3
#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED
4
5
#include <AP_HAL/AP_HAL.h>
6
#include "AP_BattMonitor.h"
7
#include "AP_BattMonitor_DroneCAN.h"
8
9
#include <AP_CANManager/AP_CANManager.h>
10
#include <AP_Common/AP_Common.h>
11
#include <GCS_MAVLink/GCS.h>
12
#include <AP_Math/AP_Math.h>
13
#include <AP_DroneCAN/AP_DroneCAN.h>
14
#include <AP_BoardConfig/AP_BoardConfig.h>
15
16
#define LOG_TAG "BattMon"
17
18
extern const AP_HAL::HAL& hal;
19
20
const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = {
21
22
// @Param: CURR_MULT
23
// @DisplayName: Scales reported power monitor current
24
// @Description: Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications
25
// @Range: .1 10
26
// @User: Advanced
27
AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0),
28
29
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
30
31
AP_GROUPEND
32
};
33
34
/// Constructor
35
AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params &params) :
36
AP_BattMonitor_Backend(mon, mon_state, params)
37
{
38
AP_Param::setup_object_defaults(this,var_info);
39
_state.var_info = var_info;
40
41
// starts with not healthy
42
_state.healthy = false;
43
}
44
45
bool AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
46
{
47
const auto driver_index = ap_dronecan->get_driver_index();
48
49
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, driver_index) != nullptr)
50
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, driver_index) != nullptr)
51
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, driver_index) != nullptr)
52
;
53
}
54
55
/*
56
match a battery ID to driver serial number
57
when serial number is negative, all batteries are accepted, otherwise it must match
58
*/
59
bool AP_BattMonitor_DroneCAN::match_battery_id(uint8_t instance, uint8_t battery_id)
60
{
61
const auto serial_num = AP::battery().get_serial_number(instance);
62
return serial_num < 0 || serial_num == (int32_t)battery_id;
63
}
64
65
AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id)
66
{
67
if (ap_dronecan == nullptr) {
68
return nullptr;
69
}
70
const auto &batt = AP::battery();
71
for (uint8_t i = 0; i < batt._num_instances; i++) {
72
if (batt.drivers[i] == nullptr ||
73
batt.allocated_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) {
74
continue;
75
}
76
AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)batt.drivers[i];
77
if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) {
78
return driver;
79
}
80
}
81
// find empty uavcan driver
82
for (uint8_t i = 0; i < batt._num_instances; i++) {
83
if (batt.drivers[i] != nullptr &&
84
batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
85
match_battery_id(i, battery_id)) {
86
87
AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i];
88
if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) {
89
continue;
90
}
91
batmon->_ap_dronecan = ap_dronecan;
92
batmon->_node_id = node_id;
93
batmon->_instance = i;
94
batmon->init();
95
AP::can().log_text(AP_CANManager::LOG_INFO,
96
LOG_TAG,
97
"Registered BattMonitor Node %d on Bus %d\n",
98
node_id,
99
ap_dronecan->get_driver_index());
100
return batmon;
101
}
102
}
103
return nullptr;
104
}
105
106
void AP_BattMonitor_DroneCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg)
107
{
108
update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct, msg.state_of_health_pct);
109
110
WITH_SEMAPHORE(_sem_battmon);
111
_remaining_capacity_wh = msg.remaining_capacity_wh;
112
_full_charge_capacity_wh = msg.full_charge_capacity_wh;
113
114
// consume state of health
115
if (msg.state_of_health_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {
116
_interim_state.state_of_health_pct = msg.state_of_health_pct;
117
_interim_state.has_state_of_health_pct = true;
118
}
119
}
120
121
void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc, uint8_t soh_pct)
122
{
123
WITH_SEMAPHORE(_sem_battmon);
124
125
_interim_state.voltage = voltage;
126
_interim_state.current_amps = _curr_mult * current;
127
_soc = soc;
128
129
if (!isnan(temperature_K) && temperature_K > 0) {
130
// Temperature reported from battery in kelvin and stored internally in Celsius.
131
_interim_state.temperature = KELVIN_TO_C(temperature_K);
132
_interim_state.temperature_time = AP_HAL::millis();
133
}
134
135
const uint32_t tnow = AP_HAL::micros();
136
137
if (!_has_battery_info_aux ||
138
!use_CAN_SoC()) {
139
const uint32_t dt_us = tnow - _interim_state.last_time_micros;
140
141
// update total current drawn since startup
142
update_consumed(_interim_state, dt_us);
143
}
144
145
// state of health
146
if (soh_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) {
147
_interim_state.state_of_health_pct = soh_pct;
148
_interim_state.has_state_of_health_pct = true;
149
}
150
151
// record time
152
_interim_state.last_time_micros = tnow;
153
_interim_state.healthy = true;
154
}
155
156
void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg)
157
{
158
WITH_SEMAPHORE(_sem_battmon);
159
uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len);
160
161
_cycle_count = msg.cycle_count;
162
for (uint8_t i = 0; i < cell_count; i++) {
163
_interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000;
164
}
165
_interim_state.is_powering_off = msg.is_powering_off;
166
if (!isnan(msg.nominal_voltage) && msg.nominal_voltage > 0) {
167
float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage;
168
float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage;
169
_interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000;
170
_interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh;
171
_interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600);
172
_interim_state.has_time_remaining = true;
173
}
174
175
_has_cell_voltages = true;
176
_has_battery_info_aux = true;
177
}
178
179
void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg)
180
{
181
const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value);
182
const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage;
183
const float current = use_input_value ? msg.input_current : msg.output_current;
184
185
// use an invalid soc so we use the library calculated one
186
const uint8_t soc = 127;
187
188
// convert C to Kelvin
189
const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature);
190
191
update_interim_state(voltage, current, temperature_K, soc, UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN);
192
193
if (!_mppt.is_detected) {
194
// this is the first time the mppt message has been received
195
// so set powered up state
196
_mppt.is_detected = true;
197
198
// Boot/Power-up event
199
if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) {
200
mppt_set_powered_state(true);
201
} else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) {
202
mppt_set_powered_state(false);
203
}
204
}
205
206
#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG
207
if (_mppt.fault_flags != msg.fault_flags) {
208
mppt_report_faults(_instance, msg.fault_flags);
209
}
210
#endif
211
_mppt.fault_flags = msg.fault_flags;
212
}
213
214
void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg)
215
{
216
AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);
217
if (driver == nullptr) {
218
return;
219
}
220
driver->handle_battery_info(msg);
221
}
222
223
void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg)
224
{
225
const auto &batt = AP::battery();
226
AP_BattMonitor_DroneCAN *driver = nullptr;
227
228
/*
229
check for a backend with AllowSplitAuxInfo set, allowing InfoAux
230
from a different CAN node than the base battery information
231
*/
232
for (uint8_t i = 0; i < batt._num_instances; i++) {
233
const auto *drv = batt.drivers[i];
234
if (drv != nullptr &&
235
batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
236
drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) &&
237
batt.get_serial_number(i) == int32_t(msg.battery_id)) {
238
driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i];
239
if (driver->_ap_dronecan == nullptr) {
240
/* we have not received the main battery information
241
yet. Discard InfoAux until we do so we can init the
242
backend with the right node ID
243
*/
244
return;
245
}
246
break;
247
}
248
}
249
if (driver == nullptr) {
250
driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id);
251
}
252
if (driver == nullptr) {
253
return;
254
}
255
driver->handle_battery_info_aux(msg);
256
}
257
258
void AP_BattMonitor_DroneCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg)
259
{
260
AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id);
261
if (driver == nullptr) {
262
return;
263
}
264
driver->handle_mppt_stream(msg);
265
}
266
267
// read - read the voltage and current
268
void AP_BattMonitor_DroneCAN::read()
269
{
270
uint32_t tnow = AP_HAL::micros();
271
272
// timeout after 5 seconds
273
if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS) {
274
_interim_state.healthy = false;
275
}
276
// Copy over relevant states over to main state
277
WITH_SEMAPHORE(_sem_battmon);
278
_state.temperature = _interim_state.temperature;
279
_state.temperature_time = _interim_state.temperature_time;
280
_state.voltage = _interim_state.voltage;
281
_state.current_amps = _interim_state.current_amps;
282
_state.consumed_mah = _interim_state.consumed_mah;
283
_state.consumed_wh = _interim_state.consumed_wh;
284
_state.last_time_micros = _interim_state.last_time_micros;
285
_state.healthy = _interim_state.healthy;
286
_state.time_remaining = _interim_state.time_remaining;
287
_state.has_time_remaining = _interim_state.has_time_remaining;
288
_state.is_powering_off = _interim_state.is_powering_off;
289
_state.state_of_health_pct = _interim_state.state_of_health_pct;
290
_state.has_state_of_health_pct = _interim_state.has_state_of_health_pct;
291
memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages));
292
293
_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
294
295
// check if MPPT should be powered on/off depending upon arming state
296
if (_mppt.is_detected) {
297
mppt_check_powered_state();
298
}
299
}
300
301
// Return true if the DroneCAN state of charge should be used.
302
// Return false if state of charge should be calculated locally by counting mah.
303
bool AP_BattMonitor_DroneCAN::use_CAN_SoC() const
304
{
305
// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then
306
// the user can set the option to use current integration in the backend instead.
307
// SOC of 127 is used as an invalid SOC flag ie system configuration errors or SOC estimation unavailable
308
return !(option_is_set(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC) ||
309
_mppt.is_detected ||
310
(_soc == 127));
311
}
312
313
/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument
314
bool AP_BattMonitor_DroneCAN::capacity_remaining_pct(uint8_t &percentage) const
315
{
316
if (!use_CAN_SoC()) {
317
return AP_BattMonitor_Backend::capacity_remaining_pct(percentage);
318
}
319
320
// the monitor must have current readings in order to estimate consumed_mah and be healthy
321
if (!has_current() || !_state.healthy) {
322
return false;
323
}
324
325
percentage = _soc;
326
return true;
327
}
328
329
// reset remaining percentage to given value
330
bool AP_BattMonitor_DroneCAN::reset_remaining(float percentage)
331
{
332
if (use_CAN_SoC()) {
333
// Cannot reset external state of charge
334
return false;
335
}
336
337
WITH_SEMAPHORE(_sem_battmon);
338
339
if (!AP_BattMonitor_Backend::reset_remaining(percentage)) {
340
// Base class reset failed
341
return false;
342
}
343
344
// Reset interim state that is used internally, this is then copied back to the main state in the read() call
345
_interim_state.consumed_mah = _state.consumed_mah;
346
_interim_state.consumed_wh = _state.consumed_wh;
347
return true;
348
}
349
350
/// get_cycle_count - return true if cycle count can be provided and fills in cycles argument
351
bool AP_BattMonitor_DroneCAN::get_cycle_count(uint16_t &cycles) const
352
{
353
if (_has_battery_info_aux) {
354
cycles = _cycle_count;
355
return true;
356
}
357
return false;
358
}
359
360
// request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS
361
void AP_BattMonitor_DroneCAN::mppt_check_powered_state()
362
{
363
if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) {
364
// there's already a set attempt that didnt' respond. Retry at 1Hz
365
mppt_set_powered_state(_mppt.powered_state);
366
}
367
368
// check if vehicle armed state has changed
369
const bool vehicle_armed = hal.util->get_soft_armed();
370
if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) {
371
// arm event
372
mppt_set_powered_state(true);
373
} else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) {
374
// disarm event
375
mppt_set_powered_state(false);
376
}
377
_mppt.vehicle_armed_last = vehicle_armed;
378
}
379
380
// request MPPT board to power on or off
381
// power_on should be true to power on the MPPT, false to power off
382
// force should be true to force sending the state change request to the MPPT
383
void AP_BattMonitor_DroneCAN::mppt_set_powered_state(bool power_on)
384
{
385
if (_ap_dronecan == nullptr || !_mppt.is_detected) {
386
return;
387
}
388
389
_mppt.powered_state = power_on;
390
391
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF",
392
(_mppt.powered_state_remote_ms == 0) ? "" : " Retry");
393
394
mppt_OutputEnableRequest request;
395
request.enable = _mppt.powered_state;
396
request.disable = !request.enable;
397
398
if (mppt_outputenable_client == nullptr) {
399
mppt_outputenable_client = NEW_NOTHROW Canard::Client<mppt_OutputEnableResponse>{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb};
400
if (mppt_outputenable_client == nullptr) {
401
return;
402
}
403
}
404
mppt_outputenable_client->request(_node_id, request);
405
}
406
407
// callback from outputEnable to verify it is enabled or disabled
408
void AP_BattMonitor_DroneCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response)
409
{
410
if (transfer.source_node_id != _node_id) {
411
// this response is not from the node we are looking for
412
return;
413
}
414
415
if (response.enabled == _mppt.powered_state) {
416
// we got back what we expected it to be. We set it on, it now says it on (or vice versa).
417
// Clear the timer so we don't re-request
418
_mppt.powered_state_remote_ms = 0;
419
}
420
}
421
422
#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG
423
// report changes in MPPT faults
424
void AP_BattMonitor_DroneCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags)
425
{
426
// handle recovery
427
if (fault_flags == 0) {
428
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: OK", (unsigned)instance+1);
429
return;
430
}
431
432
// send battery faults via text messages
433
for (uint8_t fault_bit=0x01; fault_bit <= 0x08; fault_bit <<= 1) {
434
// this loop is to generate multiple messages if there are multiple concurrent faults, but also run once if there are no faults
435
if ((fault_bit & fault_flags) != 0) {
436
const MPPT_FaultFlags err = (MPPT_FaultFlags)fault_bit;
437
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: %s", (unsigned)instance+1, mppt_fault_string(err));
438
}
439
}
440
}
441
442
// returns string description of MPPT fault bit. Only handles single bit faults
443
const char* AP_BattMonitor_DroneCAN::mppt_fault_string(const MPPT_FaultFlags fault)
444
{
445
switch (fault) {
446
case MPPT_FaultFlags::OVER_VOLTAGE:
447
return "over voltage";
448
case MPPT_FaultFlags::UNDER_VOLTAGE:
449
return "under voltage";
450
case MPPT_FaultFlags::OVER_CURRENT:
451
return "over current";
452
case MPPT_FaultFlags::OVER_TEMPERATURE:
453
return "over temp";
454
}
455
return "unknown";
456
}
457
#endif
458
459
// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)
460
uint32_t AP_BattMonitor_DroneCAN::get_mavlink_fault_bitmask() const
461
{
462
// return immediately if not mppt or no faults
463
if (!_mppt.is_detected || (_mppt.fault_flags == 0)) {
464
return 0;
465
}
466
467
// convert mppt fault bitmask to mavlink fault bitmask
468
uint32_t mav_fault_bitmask = 0;
469
if ((_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_VOLTAGE) || (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::UNDER_VOLTAGE)) {
470
mav_fault_bitmask |= MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE;
471
}
472
if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_CURRENT) {
473
mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_CURRENT;
474
}
475
if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_TEMPERATURE) {
476
mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_TEMPERATURE;
477
}
478
return mav_fault_bitmask;
479
}
480
481
#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED
482
483