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