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/battery.cpp
Views: 1798
1
#include "AP_Periph.h"
2
3
#ifdef HAL_PERIPH_ENABLE_BATTERY
4
5
/*
6
battery support
7
*/
8
9
#include <dronecan_msgs.h>
10
11
extern const AP_HAL::HAL &hal;
12
13
#ifndef AP_PERIPH_BATTERY_MODEL_NAME
14
#define AP_PERIPH_BATTERY_MODEL_NAME CAN_APP_NODE_NAME
15
#endif
16
17
/*
18
update CAN battery monitor
19
*/
20
void AP_Periph_FW::can_battery_update(void)
21
{
22
const uint32_t now_ms = AP_HAL::millis();
23
if (now_ms - battery.last_can_send_ms < 100) {
24
return;
25
}
26
battery.last_can_send_ms = now_ms;
27
28
const uint8_t battery_instances = battery_lib.num_instances();
29
for (uint8_t i=0; i<battery_instances; i++) {
30
if (BIT_IS_SET(g.battery_hide_mask, i)) {
31
// do not transmit this battery
32
continue;
33
}
34
if (!battery_lib.healthy(i)) {
35
continue;
36
}
37
38
uavcan_equipment_power_BatteryInfo pkt {};
39
40
// if a battery serial number is assigned, use that as the ID. Else, use the index.
41
const int32_t serial_number = battery_lib.get_serial_number(i);
42
pkt.battery_id = (serial_number >= 0) ? serial_number : i+1;
43
44
pkt.voltage = battery_lib.voltage(i);
45
46
float current;
47
if (battery_lib.current_amps(current, i)) {
48
pkt.current = current;
49
}
50
float temperature;
51
if (battery_lib.get_temperature(temperature, i)) {
52
// Battery lib reports temperature in Celsius.
53
// Convert Celsius to Kelvin for transmission on CAN.
54
pkt.temperature = C_TO_KELVIN(temperature);
55
}
56
57
pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;
58
uint8_t percentage = 0;
59
if (battery_lib.capacity_remaining_pct(percentage, i)) {
60
pkt.state_of_charge_pct = percentage;
61
}
62
pkt.model_instance_id = i+1;
63
64
#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME)
65
// example model_name: "org.ardupilot.ap_periph SN 123"
66
hal.util->snprintf((char*)pkt.model_name.data, sizeof(pkt.model_name.data), "%s %ld", AP_PERIPH_BATTERY_MODEL_NAME, (long int)serial_number);
67
pkt.model_name.len = strnlen((char*)pkt.model_name.data, sizeof(pkt.model_name.data));
68
#endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME)
69
70
uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE];
71
const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout());
72
73
canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE,
74
UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID,
75
CANARD_TRANSFER_PRIORITY_LOW,
76
&buffer[0],
77
total_size);
78
79
// Send individual cell information if available
80
if (battery_lib.has_cell_voltages(i)) {
81
can_battery_send_cells(i);
82
}
83
}
84
}
85
86
/*
87
send individual cell voltages if available
88
*/
89
void AP_Periph_FW::can_battery_send_cells(uint8_t instance)
90
{
91
// allocate space for the packet. This is a large
92
// packet that won't fit on the stack, so dynamically allocate
93
auto* pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;
94
uint8_t* buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
95
if (pkt == nullptr || buffer == nullptr) {
96
delete pkt;
97
delete [] buffer;
98
return;
99
}
100
const auto &cell_voltages = battery_lib.get_cell_voltages(instance);
101
102
for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) {
103
if (cell_voltages.cells[i] == 0xFFFFU) {
104
break;
105
}
106
pkt->voltage_cell.data[i] = cell_voltages.cells[i]*0.001;
107
pkt->voltage_cell.len = i+1;
108
}
109
110
pkt->max_current = nanf("");
111
pkt->nominal_voltage = nanf("");
112
113
// encode and send message:
114
const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout());
115
116
canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE,
117
ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID,
118
CANARD_TRANSFER_PRIORITY_LOW,
119
buffer,
120
total_size);
121
122
// Delete temporary buffers
123
delete pkt;
124
delete [] buffer;
125
}
126
127
#endif // HAL_PERIPH_ENABLE_BATTERY
128
129
130