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/esc_apd_telem.cpp
Views: 1798
1
/*
2
ESC Telemetry for the APD HV Pro ESC
3
4
Protocol is here: https://docs.powerdrives.net/products/hv_pro/uart-telemetry-output
5
*/
6
#include "esc_apd_telem.h"
7
#include <AP_HAL/utility/sparse-endian.h>
8
#include <AP_Math/crc.h>
9
#include <AP_Math/definitions.h>
10
#include <string.h>
11
12
#ifdef HAL_PERIPH_ENABLE_ESC_APD
13
14
extern const AP_HAL::HAL& hal;
15
16
#define TELEM_HEADER 0x9B
17
#define TELEM_LEN 0x16
18
19
ESC_APD_Telem::ESC_APD_Telem (AP_HAL::UARTDriver *_uart, float num_poles) :
20
uart(_uart),
21
pole_count(num_poles)
22
{
23
uart->begin(115200);
24
}
25
26
bool ESC_APD_Telem::update() {
27
uint32_t n = uart->available();
28
if (n == 0) {
29
return false;
30
}
31
32
// don't read too much in one loop to prevent too high CPU load
33
if (n > 50) {
34
n = 50;
35
}
36
37
bool ret = false;
38
39
while (n--) {
40
uint8_t b = uart->read();
41
received.bytes[len++] = b;
42
43
// check the packet size first
44
if ((size_t)len >= sizeof(received.packet)) {
45
// we have a full packet, check the stop byte
46
if (received.packet.stop == 65535) {
47
// valid stop byte, check the CRC
48
if (crc_fletcher16(received.bytes, 18) == received.packet.checksum) {
49
// valid packet, copy the data we need and reset length
50
decoded.voltage = le16toh(received.packet.voltage) * 1e-2f;
51
decoded.temperature = convert_temperature(le16toh(received.packet.temperature));
52
decoded.current = ((int16_t)le16toh(received.packet.bus_current)) * (1 / 12.5f);
53
decoded.rpm = le32toh(received.packet.erpm) / pole_count;
54
decoded.power_rating_pct = le16toh(received.packet.motor_duty) * 1e-2f;
55
ret = true;
56
len = 0;
57
} else {
58
// we have an invalid packet, shift it back a byte
59
shift_buffer();
60
}
61
} else {
62
// invalid stop byte, we've lost sync, shift the packet by 1 byte
63
shift_buffer();
64
}
65
66
}
67
}
68
return ret;
69
}
70
71
// shift the decode buffer left by 1 byte, and rewind the progress
72
void ESC_APD_Telem::shift_buffer(void) {
73
memmove(received.bytes, received.bytes + 1, sizeof(received.bytes) - 1);
74
len--;
75
}
76
77
// convert the raw ESC temperature to a useful value (in Kelvin)
78
// based on the 1.1 example C code found here https://docs.powerdrives.net/products/hv_pro/uart-telemetry-output
79
float ESC_APD_Telem::convert_temperature(uint16_t raw) const {
80
const float series_resistor = 10000;
81
const float nominal_resistance = 10000;
82
const float nominal_temperature = 25;
83
const float b_coefficent = 3455;
84
85
86
const float Rntc = series_resistor / ((4096 / float(raw)) - 1);
87
88
float temperature = Rntc / nominal_resistance; // (R/Ro)
89
temperature = logf(temperature); // ln(R/Ro)
90
temperature /= b_coefficent; // 1/B * ln(R/Ro)
91
temperature += 1 / C_TO_KELVIN(nominal_temperature); // + (1/To)
92
temperature = 1 / temperature; // invert
93
94
// the example code rejected anything below 0C, or above 200C, the 200C clamp makes some sense, the below 0C is harder to accept
95
return temperature;
96
}
97
98
#endif // HAL_PERIPH_ENABLE_ESC_APD
99
100