Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/battery.cpp
9414 views
1
#include "AP_Periph.h"
2
3
#if AP_PERIPH_BATTERY_ENABLED
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
// batteries should start their serial numbers at numbers above 255 to avoid conflicts with the battery index offset method of populating the serial number
42
const int32_t serial_number = battery_lib.get_serial_number(i);
43
pkt.battery_id = (serial_number >= 0) ? serial_number : i+1;
44
45
pkt.voltage = battery_lib.voltage(i);
46
47
float current;
48
if (battery_lib.current_amps(current, i)) {
49
pkt.current = current;
50
}
51
float temperature;
52
if (battery_lib.get_temperature(temperature, i)) {
53
// Battery lib reports temperature in Celsius.
54
// Convert Celsius to Kelvin for transmission on CAN.
55
pkt.temperature = C_TO_KELVIN(temperature);
56
}
57
58
// Populate state of health
59
pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;
60
uint8_t state_of_health_pct = 0;
61
if (battery_lib.get_state_of_health_pct(i, state_of_health_pct)) {
62
pkt.state_of_health_pct = state_of_health_pct;
63
}
64
65
uint8_t percentage = 0;
66
if (battery_lib.capacity_remaining_pct(percentage, i)) {
67
pkt.state_of_charge_pct = percentage;
68
}
69
pkt.model_instance_id = i+1;
70
71
#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME)
72
// example model_name: "org.ardupilot.ap_periph SN 123"
73
hal.util->snprintf((char*)pkt.model_name.data, sizeof(pkt.model_name.data), "%s %ld", AP_PERIPH_BATTERY_MODEL_NAME, (long int)serial_number);
74
pkt.model_name.len = strnlen((char*)pkt.model_name.data, sizeof(pkt.model_name.data));
75
#endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME)
76
77
uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE];
78
const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout());
79
80
canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE,
81
UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID,
82
CANARD_TRANSFER_PRIORITY_LOW,
83
&buffer[0],
84
total_size);
85
86
// Send individual cell information if available
87
if (battery_lib.has_cell_voltages(i)) {
88
can_battery_send_cells(i);
89
}
90
}
91
}
92
93
/*
94
send individual cell voltages if available
95
*/
96
void AP_Periph_FW::can_battery_send_cells(uint8_t instance)
97
{
98
// allocate space for the packet. This is a large
99
// packet that won't fit on the stack, so dynamically allocate
100
auto* pkt = NEW_NOTHROW ardupilot_equipment_power_BatteryInfoAux;
101
uint8_t* buffer = NEW_NOTHROW uint8_t[ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_MAX_SIZE];
102
if (pkt == nullptr || buffer == nullptr) {
103
delete pkt;
104
delete [] buffer;
105
return;
106
}
107
108
// fill in timestamp
109
pkt->timestamp.usec = AP_HAL::micros();
110
111
// if a battery serial number is assigned, use that as the ID. Else, use the index.
112
// batteries should start their serial numbers at numbers above 255 to avoid conflicts with the battery index offset method of populating the serial number
113
const int32_t serial_number = battery_lib.get_serial_number(instance);
114
pkt->battery_id = (serial_number >= 0) ? serial_number : instance+1;
115
116
// fill in cell voltages
117
const auto &cell_voltages = battery_lib.get_cell_voltages(instance);
118
for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) {
119
if (cell_voltages.cells[i] == 0xFFFFU) {
120
break;
121
}
122
pkt->voltage_cell.data[i] = cell_voltages.cells[i]*0.001;
123
pkt->voltage_cell.len = i+1;
124
}
125
126
// fill in max current
127
float current_amps;
128
if (battery_lib.current_amps(current_amps, instance)) {
129
pkt->max_current = current_amps;
130
} else {
131
pkt->max_current = nanf("");
132
}
133
pkt->nominal_voltage = nanf("");
134
135
// encode and send message:
136
const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout());
137
138
canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE,
139
ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID,
140
CANARD_TRANSFER_PRIORITY_LOW,
141
buffer,
142
total_size);
143
144
// Delete temporary buffers
145
delete pkt;
146
delete [] buffer;
147
}
148
149
#endif // AP_PERIPH_BATTERY_ENABLED
150
151