Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/esc_apd_telem.cpp
Views: 1798
/*1ESC Telemetry for the APD HV Pro ESC23Protocol is here: https://docs.powerdrives.net/products/hv_pro/uart-telemetry-output4*/5#include "esc_apd_telem.h"6#include <AP_HAL/utility/sparse-endian.h>7#include <AP_Math/crc.h>8#include <AP_Math/definitions.h>9#include <string.h>1011#ifdef HAL_PERIPH_ENABLE_ESC_APD1213extern const AP_HAL::HAL& hal;1415#define TELEM_HEADER 0x9B16#define TELEM_LEN 0x161718ESC_APD_Telem::ESC_APD_Telem (AP_HAL::UARTDriver *_uart, float num_poles) :19uart(_uart),20pole_count(num_poles)21{22uart->begin(115200);23}2425bool ESC_APD_Telem::update() {26uint32_t n = uart->available();27if (n == 0) {28return false;29}3031// don't read too much in one loop to prevent too high CPU load32if (n > 50) {33n = 50;34}3536bool ret = false;3738while (n--) {39uint8_t b = uart->read();40received.bytes[len++] = b;4142// check the packet size first43if ((size_t)len >= sizeof(received.packet)) {44// we have a full packet, check the stop byte45if (received.packet.stop == 65535) {46// valid stop byte, check the CRC47if (crc_fletcher16(received.bytes, 18) == received.packet.checksum) {48// valid packet, copy the data we need and reset length49decoded.voltage = le16toh(received.packet.voltage) * 1e-2f;50decoded.temperature = convert_temperature(le16toh(received.packet.temperature));51decoded.current = ((int16_t)le16toh(received.packet.bus_current)) * (1 / 12.5f);52decoded.rpm = le32toh(received.packet.erpm) / pole_count;53decoded.power_rating_pct = le16toh(received.packet.motor_duty) * 1e-2f;54ret = true;55len = 0;56} else {57// we have an invalid packet, shift it back a byte58shift_buffer();59}60} else {61// invalid stop byte, we've lost sync, shift the packet by 1 byte62shift_buffer();63}6465}66}67return ret;68}6970// shift the decode buffer left by 1 byte, and rewind the progress71void ESC_APD_Telem::shift_buffer(void) {72memmove(received.bytes, received.bytes + 1, sizeof(received.bytes) - 1);73len--;74}7576// convert the raw ESC temperature to a useful value (in Kelvin)77// based on the 1.1 example C code found here https://docs.powerdrives.net/products/hv_pro/uart-telemetry-output78float ESC_APD_Telem::convert_temperature(uint16_t raw) const {79const float series_resistor = 10000;80const float nominal_resistance = 10000;81const float nominal_temperature = 25;82const float b_coefficent = 3455;838485const float Rntc = series_resistor / ((4096 / float(raw)) - 1);8687float temperature = Rntc / nominal_resistance; // (R/Ro)88temperature = logf(temperature); // ln(R/Ro)89temperature /= b_coefficent; // 1/B * ln(R/Ro)90temperature += 1 / C_TO_KELVIN(nominal_temperature); // + (1/To)91temperature = 1 / temperature; // invert9293// the example code rejected anything below 0C, or above 200C, the 200C clamp makes some sense, the below 0C is harder to accept94return temperature;95}9697#endif // HAL_PERIPH_ENABLE_ESC_APD9899100