APM:Libraries
AP_BLHeli.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  implementation of MSP and BLHeli-4way protocols for pass-through ESC
17  calibration and firmware update
18 
19  With thanks to betaflight for a great reference implementation
20  */
21 
22 #pragma once
23 
24 #include <AP_Common/AP_Common.h>
25 #include <AP_HAL/AP_HAL.h>
26 
27 #if HAL_SUPPORT_RCOUT_SERIAL
28 
29 #include <AP_Param/AP_Param.h>
30 #include "msp_protocol.h"
31 #include "blheli_4way_protocol.h"
32 
33 class AP_BLHeli {
34 
35 public:
36  AP_BLHeli();
37 
38  void update(void);
39  void update_telemetry(void);
40  bool process_input(uint8_t b);
41 
42  static const struct AP_Param::GroupInfo var_info[];
43 
44 private:
45 
46  // mask of channels to use for BLHeli protocol
47  AP_Int32 channel_mask;
48  AP_Int8 channel_auto;
49  AP_Int8 run_test;
50  AP_Int16 timeout_sec;
51  AP_Int16 telem_rate;
52  AP_Int8 debug_level;
53  AP_Int8 output_type;
54 
55  enum mspState {
56  MSP_IDLE=0,
57  MSP_HEADER_START,
58  MSP_HEADER_M,
59  MSP_HEADER_ARROW,
60  MSP_HEADER_SIZE,
61  MSP_HEADER_CMD,
62  MSP_COMMAND_RECEIVED
63  };
64 
65  enum mspPacketType {
66  MSP_PACKET_COMMAND,
67  MSP_PACKET_REPLY
68  };
69 
70  enum escProtocol {
71  PROTOCOL_SIMONK = 0,
72  PROTOCOL_BLHELI = 1,
73  PROTOCOL_KISS = 2,
74  PROTOCOL_KISSALL = 3,
75  PROTOCOL_CASTLE = 4,
76  PROTOCOL_MAX = 5,
77  PROTOCOL_NONE = 0xfe,
78  PROTOCOL_4WAY = 0xff
79  };
80 
81  enum motorPwmProtocol {
82  PWM_TYPE_STANDARD = 0,
83  PWM_TYPE_ONESHOT125,
84  PWM_TYPE_ONESHOT42,
85  PWM_TYPE_MULTISHOT,
86  PWM_TYPE_BRUSHED,
87  PWM_TYPE_DSHOT150,
88  PWM_TYPE_DSHOT300,
89  PWM_TYPE_DSHOT600,
90  PWM_TYPE_DSHOT1200,
91  PWM_TYPE_PROSHOT1000,
92  };
93 
94  enum MSPFeatures {
95  FEATURE_RX_PPM = 1 << 0,
96  FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
97  FEATURE_RX_SERIAL = 1 << 3,
98  FEATURE_MOTOR_STOP = 1 << 4,
99  FEATURE_SERVO_TILT = 1 << 5,
100  FEATURE_SOFTSERIAL = 1 << 6,
101  FEATURE_GPS = 1 << 7,
102  FEATURE_RANGEFINDER = 1 << 9,
103  FEATURE_TELEMETRY = 1 << 10,
104  FEATURE_3D = 1 << 12,
105  FEATURE_RX_PARALLEL_PWM = 1 << 13,
106  FEATURE_RX_MSP = 1 << 14,
107  FEATURE_RSSI_ADC = 1 << 15,
108  FEATURE_LED_STRIP = 1 << 16,
109  FEATURE_DASHBOARD = 1 << 17,
110  FEATURE_OSD = 1 << 18,
111  FEATURE_CHANNEL_FORWARDING = 1 << 20,
112  FEATURE_TRANSPONDER = 1 << 21,
113  FEATURE_AIRMODE = 1 << 22,
114  FEATURE_RX_SPI = 1 << 25,
115  FEATURE_SOFTSPI = 1 << 26,
116  FEATURE_ESC_SENSOR = 1 << 27,
117  FEATURE_ANTI_GRAVITY = 1 << 28,
118  FEATURE_DYNAMIC_FILTER = 1 << 29,
119  };
120 
121 
122  /*
123  state of MSP command processing
124  */
125  struct {
126  enum mspState state;
127  enum mspPacketType packetType;
128  uint8_t offset;
129  uint8_t dataSize;
130  uint8_t checksum;
131  uint8_t buf[192];
132  uint8_t cmdMSP;
133  enum escProtocol escMode;
134  uint8_t portIndex;
135  } msp;
136 
137  enum blheliState {
138  BLHELI_IDLE=0,
139  BLHELI_HEADER_START,
140  BLHELI_HEADER_CMD,
141  BLHELI_HEADER_ADDR_LOW,
142  BLHELI_HEADER_ADDR_HIGH,
143  BLHELI_HEADER_LEN,
144  BLHELI_CRC1,
145  BLHELI_CRC2,
146  BLHELI_COMMAND_RECEIVED
147  };
148 
149  /*
150  state of blheli 4way protocol handling
151  */
152  struct {
153  enum blheliState state;
154  uint8_t command;
155  uint16_t address;
156  uint16_t param_len;
157  uint16_t offset;
158  uint8_t buf[256+3+8];
159  uint8_t crc1;
160  uint16_t crc;
161  uint8_t interface_mode;
162  uint8_t deviceInfo[4];
163  uint8_t chan;
164  uint8_t ack;
165  } blheli;
166 
167  AP_HAL::UARTDriver *uart;
168  AP_HAL::UARTDriver *debug_uart;
169  AP_HAL::UARTDriver *telem_uart;
170 
171  static const uint8_t max_motors = 8;
172  uint8_t num_motors;
173 
174  // have we initialised the interface?
175  bool initialised;
176 
177  // last valid packet timestamp
178  uint32_t last_valid_ms;
179 
180  // when did we start the serial ESC output?
181  uint32_t serial_start_ms;
182 
183  // have we disabled motor outputs?
184  bool motors_disabled;
185 
186  // have we locked the UART?
187  bool uart_locked;
188 
189  // mapping from BLHeli motor numbers to RC output channels
190  uint8_t motor_map[max_motors];
191 
192  // when did we last request telemetry?
193  uint32_t last_telem_request_us;
194  uint8_t last_telem_esc;
195  static const uint8_t telem_packet_size = 10;
196 
197  bool msp_process_byte(uint8_t c);
198  void blheli_crc_update(uint8_t c);
199  bool blheli_4way_process_byte(uint8_t c);
200  void msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len);
201  void putU16(uint8_t *b, uint16_t v);
202  uint16_t getU16(const uint8_t *b);
203  void putU32(uint8_t *b, uint32_t v);
204  void putU16_BE(uint8_t *b, uint16_t v);
205  void msp_process_command(void);
206  void blheli_send_reply(const uint8_t *buf, uint16_t len);
207  uint16_t BL_CRC(const uint8_t *buf, uint16_t len);
208  bool isMcuConnected(void);
209  void setDisconnected(void);
210  bool BL_SendBuf(const uint8_t *buf, uint16_t len);
211  bool BL_ReadBuf(uint8_t *buf, uint16_t len);
212  uint8_t BL_GetACK(uint16_t timeout_ms=2);
213  bool BL_SendCMDSetAddress();
214  bool BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n);
215  bool BL_ConnectEx(void);
216  bool BL_SendCMDKeepAlive(void);
217  bool BL_PageErase(void);
219  uint8_t BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes);
220  bool BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout);
221  uint8_t BL_WriteFlash(const uint8_t *buf, uint16_t n);
222  bool BL_VerifyFlash(const uint8_t *buf, uint16_t n);
223  void blheli_process_command(void);
224  void run_connection_test(uint8_t chan);
225  uint8_t telem_crc8(uint8_t crc, uint8_t crc_seed) const;
226  void read_telemetry_packet(void);
227 
228  // protocol handler hook
229  bool protocol_handler(uint8_t , AP_HAL::UARTDriver *);
230 };
231 
232 
233 // start of 12 byte CPU ID
234 #ifndef UDID_START
235 #define UDID_START 0x1FFF7A10
236 #endif
237 
238 #endif // HAL_SUPPORT_RCOUT_SERIAL
uint8_t BL_VerifyFlash(ioMem_t *pMem)
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
bool isMcuConnected(void)
uint8_t BL_SendCMDKeepAlive(void)
A system for managing and storing variables that are of general interest to the system.
uint8_t BL_PageErase(ioMem_t *pMem)
static int state
Definition: Util.cpp:20
float v
Definition: Printf.cpp:15
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint8_t BL_WriteFlash(ioMem_t *pMem)
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
static void run_test()
Definition: INS_generic.cpp:98