AP_BLHeli.h 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. implementation of MSP and BLHeli-4way protocols for pass-through ESC
  15. calibration and firmware update
  16. With thanks to betaflight for a great reference implementation
  17. */
  18. #pragma once
  19. #include <AP_Common/AP_Common.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #if HAL_SUPPORT_RCOUT_SERIAL
  22. #define HAVE_AP_BLHELI_SUPPORT
  23. #include <AP_Param/AP_Param.h>
  24. #include "msp_protocol.h"
  25. #include "blheli_4way_protocol.h"
  26. #define AP_BLHELI_MAX_ESCS 8
  27. class AP_BLHeli {
  28. public:
  29. AP_BLHeli();
  30. void update(void);
  31. void update_telemetry(void);
  32. bool process_input(uint8_t b);
  33. static const struct AP_Param::GroupInfo var_info[];
  34. struct telem_data {
  35. uint8_t temperature; // degrees C
  36. uint16_t voltage; // volts * 100
  37. uint16_t current; // amps * 100
  38. uint16_t consumption;// mAh
  39. uint16_t rpm; // eRPM
  40. uint16_t count;
  41. uint32_t timestamp_ms;
  42. };
  43. // get the most recent telemetry data packet for a motor
  44. bool get_telem_data(uint8_t esc_index, struct telem_data &td);
  45. static AP_BLHeli *get_singleton(void) {
  46. return _singleton;
  47. }
  48. // send ESC telemetry messages over MAVLink
  49. void send_esc_telemetry_mavlink(uint8_t mav_chan);
  50. private:
  51. static AP_BLHeli *_singleton;
  52. // mask of channels to use for BLHeli protocol
  53. AP_Int32 channel_mask;
  54. AP_Int32 channel_reversible_mask;
  55. AP_Int8 channel_auto;
  56. AP_Int8 run_test;
  57. AP_Int16 timeout_sec;
  58. AP_Int16 telem_rate;
  59. AP_Int8 debug_level;
  60. AP_Int8 output_type;
  61. AP_Int8 control_port;
  62. AP_Int8 motor_poles;
  63. enum mspState {
  64. MSP_IDLE=0,
  65. MSP_HEADER_START,
  66. MSP_HEADER_M,
  67. MSP_HEADER_ARROW,
  68. MSP_HEADER_SIZE,
  69. MSP_HEADER_CMD,
  70. MSP_COMMAND_RECEIVED
  71. };
  72. enum mspPacketType {
  73. MSP_PACKET_COMMAND,
  74. MSP_PACKET_REPLY
  75. };
  76. enum escProtocol {
  77. PROTOCOL_SIMONK = 0,
  78. PROTOCOL_BLHELI = 1,
  79. PROTOCOL_KISS = 2,
  80. PROTOCOL_KISSALL = 3,
  81. PROTOCOL_CASTLE = 4,
  82. PROTOCOL_MAX = 5,
  83. PROTOCOL_NONE = 0xfe,
  84. PROTOCOL_4WAY = 0xff
  85. };
  86. enum motorPwmProtocol {
  87. PWM_TYPE_STANDARD = 0,
  88. PWM_TYPE_ONESHOT125,
  89. PWM_TYPE_ONESHOT42,
  90. PWM_TYPE_MULTISHOT,
  91. PWM_TYPE_BRUSHED,
  92. PWM_TYPE_DSHOT150,
  93. PWM_TYPE_DSHOT300,
  94. PWM_TYPE_DSHOT600,
  95. PWM_TYPE_DSHOT1200,
  96. PWM_TYPE_PROSHOT1000,
  97. };
  98. enum MSPFeatures {
  99. FEATURE_RX_PPM = 1 << 0,
  100. FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
  101. FEATURE_RX_SERIAL = 1 << 3,
  102. FEATURE_MOTOR_STOP = 1 << 4,
  103. FEATURE_SERVO_TILT = 1 << 5,
  104. FEATURE_SOFTSERIAL = 1 << 6,
  105. FEATURE_GPS = 1 << 7,
  106. FEATURE_RANGEFINDER = 1 << 9,
  107. FEATURE_TELEMETRY = 1 << 10,
  108. FEATURE_3D = 1 << 12,
  109. FEATURE_RX_PARALLEL_PWM = 1 << 13,
  110. FEATURE_RX_MSP = 1 << 14,
  111. FEATURE_RSSI_ADC = 1 << 15,
  112. FEATURE_LED_STRIP = 1 << 16,
  113. FEATURE_DASHBOARD = 1 << 17,
  114. FEATURE_OSD = 1 << 18,
  115. FEATURE_CHANNEL_FORWARDING = 1 << 20,
  116. FEATURE_TRANSPONDER = 1 << 21,
  117. FEATURE_AIRMODE = 1 << 22,
  118. FEATURE_RX_SPI = 1 << 25,
  119. FEATURE_SOFTSPI = 1 << 26,
  120. FEATURE_ESC_SENSOR = 1 << 27,
  121. FEATURE_ANTI_GRAVITY = 1 << 28,
  122. FEATURE_DYNAMIC_FILTER = 1 << 29,
  123. };
  124. /*
  125. state of MSP command processing
  126. */
  127. struct {
  128. enum mspState state;
  129. enum mspPacketType packetType;
  130. uint8_t offset;
  131. uint8_t dataSize;
  132. uint8_t checksum;
  133. uint8_t buf[192];
  134. uint8_t cmdMSP;
  135. enum escProtocol escMode;
  136. uint8_t portIndex;
  137. } msp;
  138. enum blheliState {
  139. BLHELI_IDLE=0,
  140. BLHELI_HEADER_START,
  141. BLHELI_HEADER_CMD,
  142. BLHELI_HEADER_ADDR_LOW,
  143. BLHELI_HEADER_ADDR_HIGH,
  144. BLHELI_HEADER_LEN,
  145. BLHELI_CRC1,
  146. BLHELI_CRC2,
  147. BLHELI_COMMAND_RECEIVED
  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. bool connected[AP_BLHELI_MAX_ESCS];
  162. uint8_t interface_mode[AP_BLHELI_MAX_ESCS];
  163. uint8_t deviceInfo[AP_BLHELI_MAX_ESCS][4];
  164. uint8_t chan;
  165. uint8_t ack;
  166. } blheli;
  167. const uint16_t esc_status_addr = 0xEB00;
  168. // protocol reported by ESC in esc_status
  169. enum esc_protocol {
  170. ESC_PROTOCOL_NONE=0,
  171. ESC_PROTOCOL_NORMAL=1,
  172. ESC_PROTOCOL_ONESHOT125=2,
  173. ESC_PROTOCOL_DSHOT=5,
  174. };
  175. // ESC status structure at address 0xEB00
  176. struct PACKED esc_status {
  177. uint8_t unknown[3];
  178. enum esc_protocol protocol;
  179. uint32_t good_frames;
  180. uint32_t bad_frames;
  181. uint32_t unknown2;
  182. };
  183. AP_HAL::UARTDriver *uart;
  184. AP_HAL::UARTDriver *debug_uart;
  185. AP_HAL::UARTDriver *telem_uart;
  186. static const uint8_t max_motors = AP_BLHELI_MAX_ESCS;
  187. uint8_t num_motors;
  188. struct telem_data last_telem[max_motors];
  189. // have we initialised the interface?
  190. bool initialised;
  191. // last valid packet timestamp
  192. uint32_t last_valid_ms;
  193. // when did we start the serial ESC output?
  194. uint32_t serial_start_ms;
  195. // have we disabled motor outputs?
  196. bool motors_disabled;
  197. // have we locked the UART?
  198. bool uart_locked;
  199. // mapping from BLHeli motor numbers to RC output channels
  200. uint8_t motor_map[max_motors];
  201. uint16_t motor_mask;
  202. // when did we last request telemetry?
  203. uint32_t last_telem_request_us;
  204. uint8_t last_telem_esc;
  205. static const uint8_t telem_packet_size = 10;
  206. bool telem_uart_started;
  207. uint32_t last_telem_byte_read_us;
  208. int8_t last_control_port;
  209. bool msp_process_byte(uint8_t c);
  210. void blheli_crc_update(uint8_t c);
  211. bool blheli_4way_process_byte(uint8_t c);
  212. void msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len);
  213. void putU16(uint8_t *b, uint16_t v);
  214. uint16_t getU16(const uint8_t *b);
  215. void putU32(uint8_t *b, uint32_t v);
  216. void putU16_BE(uint8_t *b, uint16_t v);
  217. void msp_process_command(void);
  218. void blheli_send_reply(const uint8_t *buf, uint16_t len);
  219. uint16_t BL_CRC(const uint8_t *buf, uint16_t len);
  220. bool isMcuConnected(void);
  221. void setDisconnected(void);
  222. bool BL_SendBuf(const uint8_t *buf, uint16_t len);
  223. bool BL_ReadBuf(uint8_t *buf, uint16_t len);
  224. uint8_t BL_GetACK(uint16_t timeout_ms=2);
  225. bool BL_SendCMDSetAddress();
  226. bool BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n);
  227. bool BL_ConnectEx(void);
  228. bool BL_SendCMDKeepAlive(void);
  229. bool BL_PageErase(void);
  230. void BL_SendCMDRunRestartBootloader(void);
  231. uint8_t BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes);
  232. bool BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout);
  233. uint8_t BL_WriteFlash(const uint8_t *buf, uint16_t n);
  234. bool BL_VerifyFlash(const uint8_t *buf, uint16_t n);
  235. void blheli_process_command(void);
  236. void run_connection_test(uint8_t chan);
  237. uint8_t telem_crc8(uint8_t crc, uint8_t crc_seed) const;
  238. void read_telemetry_packet(void);
  239. // protocol handler hook
  240. bool protocol_handler(uint8_t , AP_HAL::UARTDriver *);
  241. };
  242. #endif // HAL_SUPPORT_RCOUT_SERIAL