forked from ArduPilot/ardupilot
/
hwing_esc.h
62 lines (49 loc) · 1.17 KB
/
hwing_esc.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
/*
ESC Telemetry for Hobbywing Pro 80A HV ESC. This will be
incorporated into a broader ESC telemetry library in ArduPilot
master in the future
*/
#pragma once
#include <AP_HAL/AP_HAL.h>
#ifdef HAL_PERIPH_ENABLE_HWESC
class HWESC_Telem {
public:
HWESC_Telem();
void init(AP_HAL::UARTDriver *uart);
bool update();
struct HWESC {
uint32_t counter;
uint16_t throttle_req;
uint16_t throttle;
uint16_t rpm;
float voltage;
uint16_t load;
float current;
uint16_t temperature;
uint16_t unknown;
};
const HWESC &get_telem(void) {
return decoded;
}
private:
AP_HAL::UARTDriver *uart;
struct PACKED {
uint8_t header; // 0x9B
uint8_t pkt_len; // 0x16
uint32_t counter;
uint16_t throttle_req;
uint16_t throttle;
uint16_t rpm;
uint16_t voltage;
int16_t current;
int16_t load;
uint16_t temperature;
uint16_t unknown;
uint16_t crc;
} pkt;
uint8_t len;
uint32_t last_read_ms;
struct HWESC decoded;
bool parse_packet(void);
};
#endif // HAL_PERIPH_ENABLE_HWESC