APM:Libraries
AP_BLHeli.cpp
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
20  implementation. Several of the functions below are based on
21  betaflight equivalent functions
22  */
23 
24 #include "AP_BLHeli.h"
25 
26 #if HAL_SUPPORT_RCOUT_SERIAL
27 
28 #include <AP_Math/crc.h>
31 #include <GCS_MAVLink/GCS.h>
33 #include <DataFlash/DataFlash.h>
34 
35 extern const AP_HAL::HAL& hal;
36 
37 #define debug(fmt, args ...) do { if (debug_level) { gcs().send_text(MAV_SEVERITY_INFO, "ESC: " fmt, ## args); } } while (0)
38 
39 // key for locking UART for exclusive use. This prevents any other writes from corrupting
40 // the MSP protocol on hal.console
41 #define BLHELI_UART_LOCK_KEY 0x20180402
42 
43 const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
44  // @Param: MASK
45  // @DisplayName: Channel Bitmask
46  // @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any)
47  // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
48  // @User: Advanced
49  AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0),
50 
51 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
52  // @Param: AUTO
53  // @DisplayName: auto-enable for multicopter motors
54  // @Description: If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors
55  // @Values: 0:Disabled,1:Enabled
56  // @User: Standard
57  AP_GROUPINFO("AUTO", 2, AP_BLHeli, channel_auto, 0),
58 #endif
59 
60  // @Param: TEST
61  // @DisplayName: internal test of BLHeli interface
62  // @Description: Setting SERVO_BLH_TEST to a motor number enables an internal test of the BLHeli ESC protocol to the corresponding ESC. The debug output is displayed on the USB console.
63  // @Values: 0:Disabled,1:TestMotor1,2:TestMotor2,3:TestMotor3,4:TestMotor4,5:TestMotor5,6:TestMotor6,7:TestMotor7,8:TestMotor8
64  // @User: Advanced
65  AP_GROUPINFO("TEST", 3, AP_BLHeli, run_test, 0),
66 
67  // @Param: TMOUT
68  // @DisplayName: BLHeli protocol timeout
69  // @Description: This sets the inactivity timeout for the BLHeli protocol in seconds. If no packets are received in this time normal MAVLink operations are resumed. A value of 0 means no timeout
70  // @Units: s
71  // @Range: 0 300
72  // @User: Standard
73  AP_GROUPINFO("TMOUT", 4, AP_BLHeli, timeout_sec, 0),
74 
75  // @Param: TRATE
76  // @DisplayName: BLHeli telemetry rate
77  // @Description: This sets the rate in Hz for requesting telemetry from ESCs. It is the rate per ESC. Setting to zero disables telemetry requests
78  // @Units: Hz
79  // @Range: 0 500
80  // @User: Standard
81  AP_GROUPINFO("TRATE", 5, AP_BLHeli, telem_rate, 0),
82 
83  // @Param: DEBUG
84  // @DisplayName: BLHeli debug level
85  // @Description: When set to 1 this enabled verbose debugging output over MAVLink when the blheli protocol is active. This can be used to diagnose failures.
86  // @Values: 0:Disabled,1:Enabled
87  // @User: Standard
88  AP_GROUPINFO("DEBUG", 6, AP_BLHeli, debug_level, 0),
89 
90  // @Param: OTYPE
91  // @DisplayName: Output type override
92  // @Description: When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group.
93  // @Values: 0:None,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200
94  // @User: Advanced
95  AP_GROUPINFO("OTYPE", 7, AP_BLHeli, output_type, 0),
96 
98 };
99 
100 // constructor
101 AP_BLHeli::AP_BLHeli(void)
102 {
103  // set defaults from the parameter table
104  AP_Param::setup_object_defaults(this, var_info);
105 }
106 
107 /*
108  process one byte of serial input for MSP protocol
109  */
110 bool AP_BLHeli::msp_process_byte(uint8_t c)
111 {
112  if (msp.state == MSP_IDLE) {
113  msp.escMode = PROTOCOL_NONE;
114  if (c == '$') {
115  msp.state = MSP_HEADER_START;
116  } else {
117  return false;
118  }
119  } else if (msp.state == MSP_HEADER_START) {
120  msp.state = (c == 'M') ? MSP_HEADER_M : MSP_IDLE;
121  } else if (msp.state == MSP_HEADER_M) {
122  msp.state = MSP_IDLE;
123  switch (c) {
124  case '<': // COMMAND
125  msp.packetType = MSP_PACKET_COMMAND;
126  msp.state = MSP_HEADER_ARROW;
127  break;
128  case '>': // REPLY
129  msp.packetType = MSP_PACKET_REPLY;
130  msp.state = MSP_HEADER_ARROW;
131  break;
132  default:
133  break;
134  }
135  } else if (msp.state == MSP_HEADER_ARROW) {
136  if (c > sizeof(msp.buf)) {
137  msp.state = MSP_IDLE;
138  } else {
139  msp.dataSize = c;
140  msp.offset = 0;
141  msp.checksum = 0;
142  msp.checksum ^= c;
143  msp.state = MSP_HEADER_SIZE;
144  }
145  } else if (msp.state == MSP_HEADER_SIZE) {
146  msp.cmdMSP = c;
147  msp.checksum ^= c;
148  msp.state = MSP_HEADER_CMD;
149  } else if (msp.state == MSP_HEADER_CMD && msp.offset < msp.dataSize) {
150  msp.checksum ^= c;
151  msp.buf[msp.offset++] = c;
152  } else if (msp.state == MSP_HEADER_CMD && msp.offset >= msp.dataSize) {
153  if (msp.checksum == c) {
154  msp.state = MSP_COMMAND_RECEIVED;
155  } else {
156  msp.state = MSP_IDLE;
157  }
158  }
159  return true;
160 }
161 
162 /*
163  update CRC state for blheli protocol
164  */
165 void AP_BLHeli::blheli_crc_update(uint8_t c)
166 {
167  blheli.crc = crc_xmodem_update(blheli.crc, c);
168 }
169 
170 /*
171  process one byte of serial input for blheli 4way protocol
172  */
173 bool AP_BLHeli::blheli_4way_process_byte(uint8_t c)
174 {
175  if (blheli.state == BLHELI_IDLE) {
176  if (c == cmd_Local_Escape) {
177  blheli.state = BLHELI_HEADER_START;
178  blheli.crc = 0;
179  blheli_crc_update(c);
180  } else {
181  return false;
182  }
183  } else if (blheli.state == BLHELI_HEADER_START) {
184  blheli.command = c;
185  blheli_crc_update(c);
186  blheli.state = BLHELI_HEADER_CMD;
187  } else if (blheli.state == BLHELI_HEADER_CMD) {
188  blheli.address = c<<8;
189  blheli.state = BLHELI_HEADER_ADDR_HIGH;
190  blheli_crc_update(c);
191  } else if (blheli.state == BLHELI_HEADER_ADDR_HIGH) {
192  blheli.address |= c;
193  blheli.state = BLHELI_HEADER_ADDR_LOW;
194  blheli_crc_update(c);
195  } else if (blheli.state == BLHELI_HEADER_ADDR_LOW) {
196  blheli.state = BLHELI_HEADER_LEN;
197  blheli.param_len = c?c:256;
198  blheli.offset = 0;
199  blheli_crc_update(c);
200  } else if (blheli.state == BLHELI_HEADER_LEN) {
201  blheli.buf[blheli.offset++] = c;
202  blheli_crc_update(c);
203  if (blheli.offset == blheli.param_len) {
204  blheli.state = BLHELI_CRC1;
205  }
206  } else if (blheli.state == BLHELI_CRC1) {
207  blheli.crc1 = c;
208  blheli.state = BLHELI_CRC2;
209  } else if (blheli.state == BLHELI_CRC2) {
210  uint16_t crc = blheli.crc1<<8 | c;
211  if (crc == blheli.crc) {
212  blheli.state = BLHELI_COMMAND_RECEIVED;
213  } else {
214  blheli.state = BLHELI_IDLE;
215  }
216  }
217  return true;
218 }
219 
220 /*
221  send a MSP protocol reply
222  */
223 void AP_BLHeli::msp_send_reply(uint8_t cmd, const uint8_t *buf, uint8_t len)
224 {
225  uint8_t *b = &msp.buf[0];
226  *b++ = '$';
227  *b++ = 'M';
228  *b++ = '>';
229  *b++ = len;
230  *b++ = cmd;
231  memcpy(b, buf, len);
232  b += len;
233  uint8_t c = 0;
234  for (uint8_t i=0; i<len+2; i++) {
235  c ^= msp.buf[i+3];
236  }
237  *b++ = c;
238  uart->write_locked(&msp.buf[0], len+6, BLHELI_UART_LOCK_KEY);
239 }
240 
241 void AP_BLHeli::putU16(uint8_t *b, uint16_t v)
242 {
243  b[0] = v;
244  b[1] = v >> 8;
245 }
246 
247 uint16_t AP_BLHeli::getU16(const uint8_t *b)
248 {
249  return b[0] | (b[1]<<8);
250 }
251 
252 void AP_BLHeli::putU32(uint8_t *b, uint32_t v)
253 {
254  b[0] = v;
255  b[1] = v >> 8;
256  b[2] = v >> 16;
257  b[3] = v >> 24;
258 }
259 
260 void AP_BLHeli::putU16_BE(uint8_t *b, uint16_t v)
261 {
262  b[0] = v >> 8;
263  b[1] = v;
264 }
265 
266 /*
267  process a MSP command from GCS
268  */
269 void AP_BLHeli::msp_process_command(void)
270 {
271  debug("MSP cmd %u len=%u", msp.cmdMSP, msp.dataSize);
272  switch (msp.cmdMSP) {
273  case MSP_API_VERSION: {
274  debug("MSP_API_VERSION");
276  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
277  break;
278  }
279 
280  case MSP_FC_VARIANT:
281  debug("MSP_FC_VARIANT");
282  msp_send_reply(msp.cmdMSP, (const uint8_t *)ARDUPILOT_IDENTIFIER, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
283  break;
284 
285  case MSP_FC_VERSION: {
286  debug("MSP_FC_VERSION");
287  uint8_t version[3] = { 3, 3, 0 };
288  msp_send_reply(msp.cmdMSP, version, sizeof(version));
289  break;
290  }
291  case MSP_BOARD_INFO: {
292  debug("MSP_BOARD_INFO");
293  // send a generic 'ArduPilot ChibiOS' board type
294  uint8_t buf[7] = { 'A', 'R', 'C', 'H', 0, 0, 0 };
295  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
296  break;
297  }
298 
299  case MSP_BUILD_INFO: {
300  debug("MSP_BUILD_INFO");
301  // build date, build time, git version
302  uint8_t buf[26] {
303  0x4d, 0x61, 0x72, 0x20, 0x31, 0x36, 0x20, 0x32, 0x30,
304  0x31, 0x38, 0x30, 0x38, 0x3A, 0x34, 0x32, 0x3a, 0x32, 0x39,
305  0x62, 0x30, 0x66, 0x66, 0x39, 0x32, 0x38};
306  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
307  break;
308  }
309 
310  case MSP_REBOOT:
311  debug("MSP: ignoring reboot command");
312  break;
313 
314  case MSP_UID:
315  // MCU identifer
316  debug("MSP_UID");
317  msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12);
318  break;
319 
320  case MSP_ADVANCED_CONFIG: {
321  debug("MSP_ADVANCED_CONFIG");
322  uint8_t buf[10];
323  buf[0] = 1; // gyro sync denom
324  buf[1] = 4; // pid process denom
325  buf[2] = 0; // use unsynced pwm
326  buf[3] = (uint8_t)PWM_TYPE_DSHOT150; // motor PWM protocol
327  putU16(&buf[4], 480); // motor PWM Rate
328  putU16(&buf[6], 450); // idle offset value
329  buf[8] = 0; // use 32kHz
330  buf[9] = 0; // motor PWM inversion
331  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
332  break;
333  }
334 
335  case MSP_FEATURE_CONFIG: {
336  debug("MSP_FEATURE_CONFIG");
337  uint8_t buf[4];
338  putU32(buf, 0); // from MSPFeatures enum
339  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
340  break;
341  }
342 
343  case MSP_STATUS: {
344  debug("MSP_STATUS");
345  uint8_t buf[21];
346  putU16(&buf[0], 1000); // loop time usec
347  putU16(&buf[2], 0); // i2c error count
348  putU16(&buf[4], 0x27); // available sensors
349  putU32(&buf[6], 0); // flight modes
350  buf[10] = 0; // pid profile index
351  putU16(&buf[11], 5); // system load percent
352  putU16(&buf[13], 0); // gyro cycle time
353  buf[15] = 0; // flight mode flags length
354  buf[16] = 18; // arming disable flags count
355  putU32(&buf[17], 0); // arming disable flags
356  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
357  break;
358  }
359 
360  case MSP_MOTOR_3D_CONFIG: {
361  debug("MSP_MOTOR_3D_CONFIG");
362  uint8_t buf[6];
363  putU16(&buf[0], 1406); // 3D deadband low
364  putU16(&buf[2], 1514); // 3D deadband high
365  putU16(&buf[4], 1460); // 3D neutral
366  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
367  break;
368  }
369 
370  case MSP_MOTOR_CONFIG: {
371  debug("MSP_MOTOR_CONFIG");
372  uint16_t min_pwm = 1000;
373  uint16_t max_pwm = 2000;
374  hal.rcout->get_esc_scaling(min_pwm, max_pwm);
375  uint8_t buf[6];
376  putU16(&buf[0], min_pwm+30); // min throttle
377  putU16(&buf[2], max_pwm); // max throttle
378  putU16(&buf[4], min_pwm); // min command
379  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
380  break;
381  }
382 
383  case MSP_MOTOR: {
384  debug("MSP_MOTOR");
385  // get the output going to each motor
386  uint8_t buf[16] {};
387  uint16_t min_pwm = 1000;
388  uint16_t max_pwm = 2000;
389  hal.rcout->get_esc_scaling(min_pwm, max_pwm);
390  for (uint8_t i = 0; i < num_motors; i++) {
391  uint16_t v = hal.rcout->read(motor_map[i]);
392  putU16(&buf[2*i], v);
393  }
394  msp_send_reply(msp.cmdMSP, buf, sizeof(buf));
395  break;
396  }
397 
398  case MSP_SET_MOTOR: {
399  debug("MSP_SET_MOTOR");
400  // set the output to each motor
401  uint8_t nmotors = msp.dataSize / 2;
402  debug("MSP_SET_MOTOR %u", nmotors);
404  motors_disabled = true;
405  hal.rcout->cork();
406  for (uint8_t i = 0; i < nmotors; i++) {
407  if (i >= num_motors) {
408  break;
409  }
410  uint16_t v = getU16(&msp.buf[i*2]);
411  debug("MSP_SET_MOTOR %u %u", i, v);
412  hal.rcout->write(motor_map[i], v);
413  }
414  hal.rcout->push();
415  break;
416  }
417 
418  case MSP_SET_4WAY_IF: {
419  debug("MSP_SET_4WAY_IF");
420  if (msp.dataSize == 0) {
421  msp.escMode = PROTOCOL_4WAY;
422  } else if (msp.dataSize == 2) {
423  msp.escMode = (enum escProtocol)msp.buf[0];
424  msp.portIndex = msp.buf[1];
425  }
426  debug("escMode=%u portIndex=%u num_motors=%u", msp.escMode, msp.portIndex, num_motors);
427  uint8_t n = num_motors;
428  switch (msp.escMode) {
429  case PROTOCOL_4WAY:
430  break;
431  default:
432  n = 0;
433  hal.rcout->serial_end();
434  serial_start_ms = 0;
435  break;
436  }
437  msp_send_reply(msp.cmdMSP, &n, 1);
438  break;
439  }
440  default:
441  debug("Unknown MSP command %u", msp.cmdMSP);
442  break;
443  }
444 }
445 
446 
447 /*
448  send a blheli 4way protocol reply
449  */
450 void AP_BLHeli::blheli_send_reply(const uint8_t *buf, uint16_t len)
451 {
452  uint8_t *b = &blheli.buf[0];
453  *b++ = cmd_Remote_Escape;
454  *b++ = blheli.command;
455  putU16_BE(b, blheli.address); b += 2;
456  *b++ = len==256?0:len;
457  memcpy(b, buf, len);
458  b += len;
459  *b++ = blheli.ack;
460  putU16_BE(b, crc_xmodem(&blheli.buf[0], len+6));
461  uart->write_locked(&blheli.buf[0], len+8, BLHELI_UART_LOCK_KEY);
462  debug("OutB(%u) 0x%02x ack=0x%02x", len+8, (unsigned)blheli.command, blheli.ack);
463 }
464 
465 /*
466  CRC used when talking to ESCs
467  */
468 uint16_t AP_BLHeli::BL_CRC(const uint8_t *buf, uint16_t len)
469 {
470  uint16_t crc = 0;
471  while (len--) {
472  uint8_t xb = *buf++;
473  for (uint8_t i = 0; i < 8; i++) {
474  if (((xb & 0x01) ^ (crc & 0x0001)) !=0 ) {
475  crc = crc >> 1;
476  crc = crc ^ 0xA001;
477  } else {
478  crc = crc >> 1;
479  }
480  xb = xb >> 1;
481  }
482  }
483  return crc;
484 }
485 
486 bool AP_BLHeli::isMcuConnected(void)
487 {
488  return blheli.deviceInfo[0] > 0;
489 }
490 
491 void AP_BLHeli::setDisconnected(void)
492 {
493  blheli.deviceInfo[0] = 0;
494  blheli.deviceInfo[1] = 0;
495 }
496 
497 /*
498  send a set of bytes to an RC output channel
499  */
500 bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)
501 {
502  bool send_crc = isMcuConnected();
503  if (blheli.chan >= num_motors) {
504  return false;
505  }
506  if (!hal.rcout->serial_setup_output(motor_map[blheli.chan], 19200)) {
507  blheli.ack = ACK_D_GENERAL_ERROR;
508  return false;
509  }
510  if (serial_start_ms == 0) {
511  serial_start_ms = AP_HAL::millis();
512  }
513  uint32_t now = AP_HAL::millis();
514  if (serial_start_ms == 0 || now - serial_start_ms < 1000) {
515  /*
516  we've just started the interface. We want it idle for at
517  least 1 second before we start sending serial data.
518  */
519  hal.scheduler->delay(1100);
520  } else {
521  hal.scheduler->delay(10);
522  }
523  memcpy(blheli.buf, buf, len);
524  uint16_t crc = BL_CRC(buf, len);
525  blheli.buf[len] = crc;
526  blheli.buf[len+1] = crc>>8;
527  if (!hal.rcout->serial_write_bytes(blheli.buf, len+(send_crc?2:0))) {
528  blheli.ack = ACK_D_GENERAL_ERROR;
529  return false;
530  }
531  return true;
532 }
533 
534 /*
535  read bytes from the ESC connection
536  */
537 bool AP_BLHeli::BL_ReadBuf(uint8_t *buf, uint16_t len)
538 {
539  bool check_crc = isMcuConnected() && len > 0;
540  uint16_t req_bytes = len+(check_crc?3:1);
541  uint16_t n = hal.rcout->serial_read_bytes(blheli.buf, req_bytes);
542  debug("BL_ReadBuf %u -> %u", len, n);
543  if (req_bytes != n) {
544  debug("short read");
545  blheli.ack = ACK_D_GENERAL_ERROR;
546  return false;
547  }
548  if (check_crc) {
549  uint16_t crc = BL_CRC(blheli.buf, len);
550  if ((crc & 0xff) != blheli.buf[len] ||
551  (crc >> 8) != blheli.buf[len+1]) {
552  debug("bad CRC");
553  blheli.ack = ACK_D_GENERAL_ERROR;
554  return false;
555  }
556  if (blheli.buf[len+2] != brSUCCESS) {
557  debug("bad ACK 0x%02x", blheli.buf[len+2]);
558  blheli.ack = ACK_D_GENERAL_ERROR;
559  return false;
560  }
561  } else {
562  if (blheli.buf[len] != brSUCCESS) {
563  debug("bad ACK1 0x%02x", blheli.buf[len]);
564  blheli.ack = ACK_D_GENERAL_ERROR;
565  return false;
566  }
567  }
568  if (len > 0) {
569  memcpy(buf, blheli.buf, len);
570  }
571  return true;
572 }
573 
574 uint8_t AP_BLHeli::BL_GetACK(uint16_t timeout_ms)
575 {
576  uint8_t ack;
577  uint32_t start_ms = AP_HAL::millis();
578  while (AP_HAL::millis() - start_ms < timeout_ms) {
579  if (hal.rcout->serial_read_bytes(&ack, 1) == 1) {
580  return ack;
581  }
582  }
583  // return brNONE, meaning no ACK received in the timeout
584  return brNONE;
585 }
586 
587 bool AP_BLHeli::BL_SendCMDSetAddress()
588 {
589  // skip if adr == 0xFFFF
590  if (blheli.address == 0xFFFF) {
591  return true;
592  }
593  debug("BL_SendCMDSetAddress 0x%04x", blheli.address);
594  uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, uint8_t(blheli.address>>8), uint8_t(blheli.address)};
595  if (!BL_SendBuf(sCMD, 4)) {
596  return false;
597  }
598  return BL_GetACK() == brSUCCESS;
599 }
600 
601 bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)
602 {
603  if (BL_SendCMDSetAddress()) {
604  uint8_t sCMD[] = {cmd, uint8_t(n==256?0:n)};
605  if (!BL_SendBuf(sCMD, 2)) {
606  return false;
607  }
608  return BL_ReadBuf(buf, n);
609  }
610  return false;
611 }
612 
613 /*
614  connect to a blheli ESC
615  */
616 bool AP_BLHeli::BL_ConnectEx(void)
617 {
618  debug("BL_ConnectEx %u/%u at %u", blheli.chan, num_motors, motor_map[blheli.chan]);
619  setDisconnected();
620  const uint8_t BootInit[] = {0,0,0,0,0,0,0,0,0,0,0,0,0x0D,'B','L','H','e','l','i',0xF4,0x7D};
621  if (!BL_SendBuf(BootInit, 21)) {
622  return false;
623  }
624 
625  uint8_t BootInfo[8];
626  if (!BL_ReadBuf(BootInfo, 8)) {
627  return false;
628  }
629 
630  // reply must start with 471
631  if (strncmp((const char *)BootInfo, "471", 3) != 0) {
632  blheli.ack = ACK_D_GENERAL_ERROR;
633  return false;
634  }
635 
636  // extract device information
637  blheli.deviceInfo[2] = BootInfo[3];
638  blheli.deviceInfo[1] = BootInfo[4];
639  blheli.deviceInfo[0] = BootInfo[5];
640 
641  blheli.interface_mode = 0;
642 
643  uint16_t *devword = (uint16_t *)blheli.deviceInfo;
644  switch (*devword) {
645  case 0x9307:
646  case 0x930A:
647  case 0x930F:
648  case 0x940B:
649  blheli.interface_mode = imATM_BLB;
650  debug("Interface type imATM_BLB");
651  break;
652  case 0xF310:
653  case 0xF330:
654  case 0xF410:
655  case 0xF390:
656  case 0xF850:
657  case 0xE8B1:
658  case 0xE8B2:
659  blheli.interface_mode = imSIL_BLB;
660  debug("Interface type imSIL_BLB");
661  break;
662  case 0x1F06:
663  case 0x3306:
664  case 0x3406:
665  case 0x3506:
666  blheli.interface_mode = imARM_BLB;
667  debug("Interface type imARM_BLB");
668  break;
669  default:
670  blheli.ack = ACK_D_GENERAL_ERROR;
671  debug("Unknown interface type 0x%04x", *devword);
672  break;
673  }
674  blheli.deviceInfo[3] = blheli.interface_mode;
675  return true;
676 }
677 
679 {
680  uint8_t sCMD[] = {CMD_KEEP_ALIVE, 0};
681  if (!BL_SendBuf(sCMD, 2)) {
682  return false;
683  }
684  if (BL_GetACK() != brERRORCOMMAND) {
685  return false;
686  }
687  return true;
688 }
689 
690 bool AP_BLHeli::BL_PageErase(void)
691 {
692  if (BL_SendCMDSetAddress()) {
693  uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
694  if (!BL_SendBuf(sCMD, 2)) {
695  return false;
696  }
697  return BL_GetACK(1000) == brSUCCESS;
698  }
699  return false;
700 }
701 
703 {
704  uint8_t sCMD[] = {RestartBootloader, 0};
705  blheli.deviceInfo[0] = 1;
706  BL_SendBuf(sCMD, 2);
707 }
708 
709 uint8_t AP_BLHeli::BL_SendCMDSetBuffer(const uint8_t *buf, uint16_t nbytes)
710 {
711  uint8_t sCMD[] = {CMD_SET_BUFFER, 0, uint8_t(nbytes>>8), uint8_t(nbytes&0xff)};
712  if (!BL_SendBuf(sCMD, 4)) {
713  return false;
714  }
715  uint8_t ack;
716  if ((ack = BL_GetACK()) != brNONE) {
717  debug("BL_SendCMDSetBuffer ack failed 0x%02x", ack);
718  blheli.ack = ACK_D_GENERAL_ERROR;
719  return false;
720  }
721  if (!BL_SendBuf(buf, nbytes)) {
722  debug("BL_SendCMDSetBuffer send failed");
723  blheli.ack = ACK_D_GENERAL_ERROR;
724  return false;
725  }
726  return (BL_GetACK(40) == brSUCCESS);
727 }
728 
729 bool AP_BLHeli::BL_WriteA(uint8_t cmd, const uint8_t *buf, uint16_t nbytes, uint32_t timeout_ms)
730 {
731  if (BL_SendCMDSetAddress()) {
732  if (!BL_SendCMDSetBuffer(buf, nbytes)) {
733  blheli.ack = ACK_D_GENERAL_ERROR;
734  return false;
735  }
736  uint8_t sCMD[] = {cmd, 0x01};
737  if (!BL_SendBuf(sCMD, 2)) {
738  return false;
739  }
740  return (BL_GetACK(timeout_ms) == brSUCCESS);
741  }
742  blheli.ack = ACK_D_GENERAL_ERROR;
743  return false;
744 }
745 
746 uint8_t AP_BLHeli::BL_WriteFlash(const uint8_t *buf, uint16_t n)
747 {
748  return BL_WriteA(CMD_PROG_FLASH, buf, n, 250);
749 }
750 
751 bool AP_BLHeli::BL_VerifyFlash(const uint8_t *buf, uint16_t n)
752 {
753  if (BL_SendCMDSetAddress()) {
754  if (!BL_SendCMDSetBuffer(buf, n)) {
755  return false;
756  }
757  uint8_t sCMD[] = {CMD_VERIFY_FLASH_ARM, 0x01};
758  if (!BL_SendBuf(sCMD, 2)) {
759  return false;
760  }
761  uint8_t ack = BL_GetACK(40);
762  switch (ack) {
763  case brSUCCESS:
764  blheli.ack = ACK_OK;
765  break;
766  case brERRORVERIFY:
767  blheli.ack = ACK_I_VERIFY_ERROR;
768  break;
769  default:
770  blheli.ack = ACK_D_GENERAL_ERROR;
771  break;
772  }
773  return true;
774  }
775  return false;
776 }
777 
778 /*
779  process a blheli 4way command from GCS
780  */
781 void AP_BLHeli::blheli_process_command(void)
782 {
783  debug("BLHeli cmd 0x%02x len=%u", blheli.command, blheli.param_len);
784  blheli.ack = ACK_OK;
785  switch (blheli.command) {
786  case cmd_InterfaceTestAlive: {
787  debug("cmd_InterfaceTestAlive");
789  if (blheli.ack != ACK_OK) {
790  setDisconnected();
791  }
792  uint8_t b = 0;
793  blheli_send_reply(&b, 1);
794  break;
795  }
796  case cmd_ProtocolGetVersion: {
797  debug("cmd_ProtocolGetVersion");
798  uint8_t buf[1];
799  buf[0] = SERIAL_4WAY_PROTOCOL_VER;
800  blheli_send_reply(buf, sizeof(buf));
801  break;
802  }
803  case cmd_InterfaceGetName: {
804  debug("cmd_InterfaceGetName");
805  uint8_t buf[5] = { 4, 'A', 'R', 'D', 'U' };
806  blheli_send_reply(buf, sizeof(buf));
807  break;
808  }
810  debug("cmd_InterfaceGetVersion");
811  uint8_t buf[2] = { SERIAL_4WAY_VERSION_HI, SERIAL_4WAY_VERSION_LO };
812  blheli_send_reply(buf, sizeof(buf));
813  break;
814  }
815  case cmd_InterfaceExit: {
816  debug("cmd_InterfaceExit");
817  msp.escMode = PROTOCOL_NONE;
818  uint8_t b = 0;
819  blheli_send_reply(&b, 1);
820  hal.rcout->serial_end();
821  serial_start_ms = 0;
822  if (motors_disabled) {
823  motors_disabled = false;
825  }
826  if (uart_locked) {
827  debug("Unlocked UART");
828  uart->lock_port(0);
829  uart_locked = false;
830  }
831  break;
832  }
833  case cmd_DeviceReset: {
834  debug("cmd_DeviceReset(%u)", unsigned(blheli.buf[0]));
835  blheli.chan = blheli.buf[0];
836  switch (blheli.interface_mode) {
837  case imSIL_BLB:
838  case imATM_BLB:
839  case imARM_BLB:
841  break;
842  case imSK:
843  break;
844  }
845  blheli_send_reply(&blheli.chan, 1);
846  setDisconnected();
847  break;
848  }
849 
850  case cmd_DeviceInitFlash: {
851  debug("cmd_DeviceInitFlash(%u)", unsigned(blheli.buf[0]));
852  blheli.chan = blheli.buf[0];
853  for (uint8_t tries=0; tries<5; tries++) {
854  blheli.ack = ACK_OK;
855  setDisconnected();
856  if (BL_ConnectEx()) {
857  break;
858  }
859  }
860  uint8_t buf[4] = {blheli.deviceInfo[0],
861  blheli.deviceInfo[1],
862  blheli.deviceInfo[2],
863  blheli.deviceInfo[3]}; // device ID
864  blheli_send_reply(buf, sizeof(buf));
865  break;
866  }
867 
868  case cmd_InterfaceSetMode: {
869  debug("cmd_InterfaceSetMode(%u)", unsigned(blheli.buf[0]));
870  blheli.interface_mode = blheli.buf[0];
871  blheli_send_reply(&blheli.interface_mode, 1);
872  break;
873  }
874 
875  case cmd_DeviceRead: {
876  uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
877  debug("cmd_DeviceRead(%u) n=%u", blheli.chan, nbytes);
878  uint8_t buf[nbytes];
879  uint8_t cmd = blheli.interface_mode==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;
880  if (!BL_ReadA(cmd, buf, nbytes)) {
881  nbytes = 1;
882  }
883  blheli_send_reply(buf, nbytes);
884  break;
885  }
886 
887  case cmd_DevicePageErase: {
888  uint8_t page = blheli.buf[0];
889  debug("cmd_DevicePageErase(%u) im=%u", page, blheli.interface_mode);
890  switch (blheli.interface_mode) {
891  case imSIL_BLB:
892  case imARM_BLB: {
893  if (blheli.interface_mode == imARM_BLB) {
894  // Address =Page * 1024
895  blheli.address = page << 10;
896  } else {
897  // Address =Page * 512
898  blheli.address = page << 9;
899  }
900  debug("ARM PageErase 0x%04x", blheli.address);
901  BL_PageErase();
902  blheli.address = 0;
903  blheli_send_reply(&page, 1);
904  break;
905  }
906  default:
907  blheli.ack = ACK_I_INVALID_CMD;
908  blheli_send_reply(&page, 1);
909  break;
910  }
911  break;
912  }
913 
914  case cmd_DeviceWrite: {
915  uint16_t nbytes = blheli.param_len;
916  debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode);
917  uint8_t buf[nbytes];
918  memcpy(buf, blheli.buf, nbytes);
919  switch (blheli.interface_mode) {
920  case imSIL_BLB:
921  case imATM_BLB:
922  case imARM_BLB: {
923  BL_WriteFlash(buf, nbytes);
924  break;
925  }
926  case imSK: {
927  debug("Unsupported flash mode imSK");
928  break;
929  }
930  }
931  uint8_t b=0;
932  blheli_send_reply(&b, 1);
933  break;
934  }
935 
936  case cmd_DeviceVerify: {
937  uint16_t nbytes = blheli.param_len;
938  debug("cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode);
939  switch (blheli.interface_mode) {
940  case imARM_BLB: {
941  uint8_t buf[nbytes];
942  memcpy(buf, blheli.buf, nbytes);
943  BL_VerifyFlash(buf, nbytes);
944  break;
945  }
946  default:
947  blheli.ack = ACK_I_INVALID_CMD;
948  break;
949  }
950  uint8_t b=0;
951  blheli_send_reply(&b, 1);
952  break;
953  }
954 
955  case cmd_DeviceReadEEprom: {
956  uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
957  uint8_t buf[nbytes];
958  debug("cmd_DeviceReadEEprom n=%u im=%u", nbytes, blheli.interface_mode);
959  switch (blheli.interface_mode) {
960  case imATM_BLB: {
961  if (!BL_ReadA(CMD_READ_EEPROM, buf, nbytes)) {
962  blheli.ack = ACK_D_GENERAL_ERROR;
963  }
964  break;
965  }
966  default:
967  blheli.ack = ACK_I_INVALID_CMD;
968  break;
969  }
970  if (blheli.ack != ACK_OK) {
971  nbytes = 1;
972  buf[0] = 0;
973  }
974  blheli_send_reply(buf, nbytes);
975  break;
976  }
977 
978  case cmd_DeviceWriteEEprom: {
979  uint16_t nbytes = blheli.param_len;
980  uint8_t buf[nbytes];
981  memcpy(buf, blheli.buf, nbytes);
982  debug("cmd_DeviceWriteEEprom n=%u im=%u", nbytes, blheli.interface_mode);
983  switch (blheli.interface_mode) {
984  case imATM_BLB:
985  BL_WriteA(CMD_PROG_EEPROM, buf, nbytes, 1000);
986  break;
987  default:
988  blheli.ack = ACK_D_GENERAL_ERROR;
989  break;
990  }
991  uint8_t b = 0;
992  blheli_send_reply(&b, 1);
993  break;
994  }
995 
996  case cmd_DeviceEraseAll:
997  case cmd_DeviceC2CK_LOW:
998  default:
999  // ack=unknown command
1000  blheli.ack = ACK_I_INVALID_CMD;
1001  debug("Unknown BLHeli protocol 0x%02x", blheli.command);
1002  uint8_t b = 0;
1003  blheli_send_reply(&b, 1);
1004  break;
1005  }
1006 }
1007 
1008 /*
1009  process an input byte, return true if we have received a whole
1010  packet with correct CRC
1011  */
1012 bool AP_BLHeli::process_input(uint8_t b)
1013 {
1014  bool valid_packet = false;
1015 
1016  if (msp.escMode == PROTOCOL_4WAY && blheli.state == BLHELI_IDLE && b == '$') {
1017  debug("Change to MSP mode");
1018  msp.escMode = PROTOCOL_NONE;
1019  hal.rcout->serial_end();
1020  serial_start_ms = 0;
1021  }
1022  if (msp.escMode != PROTOCOL_4WAY && msp.state == MSP_IDLE && b == '/') {
1023  debug("Change to BLHeli mode");
1024  msp.escMode = PROTOCOL_4WAY;
1025  }
1026  if (msp.escMode == PROTOCOL_4WAY) {
1027  blheli_4way_process_byte(b);
1028  } else {
1029  msp_process_byte(b);
1030  }
1031  if (msp.escMode == PROTOCOL_4WAY) {
1032  if (blheli.state == BLHELI_COMMAND_RECEIVED) {
1033  valid_packet = true;
1034  last_valid_ms = AP_HAL::millis();
1035  if (uart->lock_port(BLHELI_UART_LOCK_KEY)) {
1036  uart_locked = true;
1037  }
1038  blheli_process_command();
1039  blheli.state = BLHELI_IDLE;
1040  msp.state = MSP_IDLE;
1041  }
1042  } else if (msp.state == MSP_COMMAND_RECEIVED) {
1043  if (msp.packetType == MSP_PACKET_COMMAND) {
1044  valid_packet = true;
1045  if (uart->lock_port(BLHELI_UART_LOCK_KEY)) {
1046  uart_locked = true;
1047  }
1048  last_valid_ms = AP_HAL::millis();
1049  msp_process_command();
1050  }
1051  msp.state = MSP_IDLE;
1052  blheli.state = BLHELI_IDLE;
1053  }
1054 
1055  return valid_packet;
1056 }
1057 
1058 /*
1059  protocol handler for detecting BLHeli input
1060  */
1061 bool AP_BLHeli::protocol_handler(uint8_t b, AP_HAL::UARTDriver *_uart)
1062 {
1063  uart = _uart;
1064  if (hal.util->get_soft_armed()) {
1065  // don't allow MSP control when armed
1066  return false;
1067  }
1068  return process_input(b);
1069 }
1070 
1071 
1072 /*
1073  run a connection test to the ESCs. This is used to test the
1074  operation of the BLHeli ESC protocol
1075 */
1076 void AP_BLHeli::run_connection_test(uint8_t chan)
1077 {
1078  debug_uart = hal.console;
1079  uint8_t saved_chan = blheli.chan;
1080  blheli.chan = chan;
1081  debug("Running test on channel %u", blheli.chan);
1082  run_test.set_and_notify(0);
1083  bool passed = false;
1084  for (uint8_t tries=0; tries<5; tries++) {
1085  blheli.ack = ACK_OK;
1086  setDisconnected();
1087  if (BL_ConnectEx()) {
1088  uint8_t buf[256];
1089  uint8_t cmd = blheli.interface_mode==imATM_BLB?CMD_READ_FLASH_ATM:CMD_READ_FLASH_SIL;
1090  passed = true;
1091  blheli.address = blheli.interface_mode==imATM_BLB?0:0x7c00;
1092  passed &= BL_ReadA(cmd, buf, sizeof(buf));
1094  break;
1095  }
1096  }
1097  hal.rcout->serial_end();
1099  motors_disabled = false;
1100  serial_start_ms = 0;
1101  blheli.chan = saved_chan;
1102  debug("Test %s", passed?"PASSED":"FAILED");
1103  debug_uart = nullptr;
1104 }
1105 
1106 /*
1107  update BLHeli
1108  Used to install protocol handler
1109  */
1110 void AP_BLHeli::update(void)
1111 {
1112  if (initialised &&
1113  timeout_sec &&
1114  uart_locked &&
1115  AP_HAL::millis() - last_valid_ms > uint32_t(timeout_sec.get())*1000U) {
1116  // we're not processing requests any more, shutdown serial
1117  // output
1118  if (serial_start_ms) {
1119  hal.rcout->serial_end();
1120  serial_start_ms = 0;
1121  }
1122  if (motors_disabled) {
1123  motors_disabled = false;
1125  }
1126  debug("Unlocked UART");
1127  uart->lock_port(0);
1128  uart_locked = false;
1129  }
1130  if (initialised || (channel_mask.get() == 0 && channel_auto.get() == 0)) {
1131  if (initialised && run_test.get() > 0) {
1132  run_connection_test(run_test.get() - 1);
1133  }
1134  return;
1135  }
1136  initialised = true;
1137 
1138  run_test.set_and_notify(0);
1139 
1140  if (gcs().install_alternative_protocol(MAVLINK_COMM_0,
1141  FUNCTOR_BIND_MEMBER(&AP_BLHeli::protocol_handler,
1142  bool, uint8_t, AP_HAL::UARTDriver *))) {
1143  debug("BLHeli installed");
1144  }
1145 
1146  uint16_t mask = uint16_t(channel_mask.get());
1147 
1148  /*
1149  allow mode override - this makes it possible to use DShot for
1150  rovers and subs, plus for quadplane fwd motors
1151  */
1153  switch (AP_Motors::pwm_type(output_type.get())) {
1156  break;
1159  break;
1162  break;
1165  break;
1168  break;
1171  break;
1174  break;
1175  default:
1176  break;
1177  }
1178  if (mask && mode != AP_HAL::RCOutput::MODE_PWM_NONE) {
1179  hal.rcout->set_output_mode(mask, mode);
1180  }
1181 
1182 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1183  /*
1184  plane and copter can use AP_Motors to get an automatic mask
1185  */
1186  if (channel_auto.get() == 1) {
1188  if (motors) {
1189  mask |= motors->get_motor_mask();
1190  }
1191  }
1192 #endif
1193 
1194  // add motors from channel mask
1195  for (uint8_t i=0; i<16 && num_motors < max_motors; i++) {
1196  if (mask & (1U<<i)) {
1197  motor_map[num_motors] = i;
1198  num_motors++;
1199  }
1200  }
1201  debug("ESC: %u motors mask=0x%04x", num_motors, mask);
1202 
1203  if (telem_rate > 0) {
1205  if (serial_manager) {
1206  telem_uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_ESCTelemetry,0);
1207  }
1208  }
1209 
1210 }
1211 
1212 /*
1213  implement the 8 bit CRC used by the BLHeli ESC telemetry protocol
1214  */
1215 uint8_t AP_BLHeli::telem_crc8(uint8_t crc, uint8_t crc_seed) const
1216 {
1217  uint8_t crc_u = crc;
1218  crc_u ^= crc_seed;
1219 
1220  for (uint8_t i=0; i<8; i++) {
1221  crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
1222  }
1223 
1224  return crc_u;
1225 }
1226 
1227 /*
1228  read an ESC telemetry packet
1229  */
1230 void AP_BLHeli::read_telemetry_packet(void)
1231 {
1232  uint8_t buf[telem_packet_size];
1233  uint8_t crc = 0;
1234  for (uint8_t i=0; i<telem_packet_size; i++) {
1235  int16_t v = telem_uart->read();
1236  if (v < 0) {
1237  // short read, we should have 10 bytes ready when this function is called
1238  return;
1239  }
1240  buf[i] = uint8_t(v);
1241  }
1242 
1243  // calculate crc
1244  for (uint8_t i=0; i<telem_packet_size-1; i++) {
1245  crc = telem_crc8(buf[i], crc);
1246  }
1247 
1248  if (buf[telem_packet_size-1] != crc) {
1249  // bad crc
1250  debug("Bad CRC on %u\n", last_telem_esc);
1251  return;
1252  }
1253  uint8_t temperature = buf[0];
1254  uint16_t voltage = (buf[1]<<8) | buf[2];
1255  uint16_t current = (buf[3]<<8) | buf[4];
1256  uint16_t consumption = (buf[5]<<8) | buf[6];
1257  uint16_t rpm = (buf[7]<<8) | buf[8];
1258 
1260  if (df && df->logging_enabled()) {
1261  struct log_Esc pkt = {
1262  LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC1_MSG+last_telem_esc)),
1264  rpm : int32_t(rpm*100U),
1265  voltage : uint16_t(voltage),
1266  current : uint16_t(current),
1267  temperature : int16_t(temperature * 100U),
1268  current_tot : consumption
1269  };
1270  df->WriteBlock(&pkt, sizeof(pkt));
1271  }
1272 #if 0
1273  hal.console->printf("ESC[%u] T=%u V=%u C=%u con=%u RPM=%u\n",
1274  last_telem_esc,
1275  temperature,
1276  voltage,
1277  current,
1278  consumption,
1279  rpm);
1280 #endif
1281 }
1282 
1283 /*
1284  update BLHeli telemetry handling
1285  This is called on push() in SRV_Channels
1286  */
1287 void AP_BLHeli::update_telemetry(void)
1288 {
1289  if (!telem_uart) {
1290  return;
1291  }
1292  uint32_t now = AP_HAL::micros();
1293  uint32_t nbytes = telem_uart->available();
1294  uint32_t telem_rate_us = 1000000U / uint32_t(telem_rate.get() * num_motors);
1295  if (telem_rate_us < 2000) {
1296  // make sure we have a gap between frames
1297  telem_rate_us = 2000;
1298  }
1299 
1300  if (nbytes > telem_packet_size) {
1301  // if we have more than 10 bytes then we don't know which ESC
1302  // they are from. Throw them all away
1303  if (nbytes > telem_packet_size*2) {
1304  // something badly wrong with this uart, disable ESC
1305  // telemetry so we don't chew lots of CPU reading garbage
1306  telem_uart = nullptr;
1307  return;
1308  }
1309  while (nbytes--) {
1310  telem_uart->read();
1311  }
1312  return;
1313  }
1314  if (nbytes > 0 &&
1315  nbytes < telem_packet_size &&
1316  now - last_telem_request_us < telem_rate_us) {
1317  // wait a bit longer, we don't have enough bytes yet
1318  return;
1319  }
1320  if (nbytes > 0 && nbytes < telem_packet_size) {
1321  // we've waited long enough, discard bytes if we don't have 10 yet
1322  while (nbytes--) {
1323  telem_uart->read();
1324  }
1325  return;
1326  }
1327  if (nbytes == telem_packet_size) {
1328  // we have a full packet ready to parse
1329  read_telemetry_packet();
1330  }
1331  if (now - last_telem_request_us >= telem_rate_us) {
1332  last_telem_esc = (last_telem_esc + 1) % num_motors;
1333  uint16_t mask = 1U << motor_map[last_telem_esc];
1334  hal.rcout->set_telem_request_mask(mask);
1335  last_telem_request_us = now;
1336  }
1337 }
1338 
1339 #endif // HAL_SUPPORT_RCOUT_SERIAL
bool get_soft_armed() const
Definition: Util.h:15
uint8_t BL_VerifyFlash(ioMem_t *pMem)
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
uint16_t current
Definition: LogStructure.h:834
#define cmd_InterfaceGetName
#define CMD_SET_ADDRESS
uint16_t crc_xmodem(const uint8_t *data, uint16_t len)
Definition: crc.cpp:82
#define ACK_D_GENERAL_ERROR
#define ACK_OK
#define MSP_PROTOCOL_VERSION
Definition: msp_protocol.h:65
#define cmd_InterfaceSetMode
#define CMD_READ_EEPROM
bool logging_enabled() const
Definition: DataFlash.cpp:365
#define imATM_BLB
virtual uint16_t read(uint8_t ch)=0
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define MSP_ADVANCED_CONFIG
Definition: msp_protocol.h:210
Interface definition for the various Ground Control System.
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data)
Definition: crc.cpp:67
#define brERRORVERIFY
#define MSP_BUILD_INFO
Definition: msp_protocol.h:106
#define cmd_DeviceWriteEEprom
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define cmd_DeviceC2CK_LOW
#define imSK
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
#define imSIL_BLB
AP_HAL::Util * util
Definition: HAL.h:115
#define MSP_MOTOR
Definition: msp_protocol.h:254
#define SERIAL_4WAY_VERSION_HI
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define cmd_Local_Escape
GCS & gcs()
#define ACK_I_INVALID_CMD
uint16_t current_tot
Definition: LogStructure.h:836
static AP_Motors * get_instance(void)
#define cmd_InterfaceTestAlive
#define MSP_API_VERSION
Definition: msp_protocol.h:102
bool isMcuConnected(void)
#define CMD_KEEP_ALIVE
#define debug(fmt, args ...)
#define MSP_STATUS
Definition: msp_protocol.h:251
#define MSP_MOTOR_CONFIG
Definition: msp_protocol.h:283
#define MSP_SET_4WAY_IF
Definition: msp_protocol.h:333
#define CMD_PROG_FLASH
uint8_t BL_SendCMDKeepAlive(void)
AP_MotorsMatrix motors(400)
float temperature
Definition: Airspeed.cpp:32
virtual void delay(uint16_t ms)=0
#define brNONE
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define MSP_MOTOR_3D_CONFIG
Definition: msp_protocol.h:276
#define cmd_ProtocolGetVersion
#define cmd_InterfaceGetVersion
#define cmd_DeviceReadEEprom
virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm)
Definition: RCOutput.h:116
#define brERRORCOMMAND
uint8_t BL_PageErase(ioMem_t *pMem)
uint32_t millis()
Definition: system.cpp:157
virtual uint16_t get_motor_mask()=0
#define CMD_VERIFY_FLASH_ARM
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
virtual void set_telem_request_mask(uint16_t mask)
Definition: RCOutput.h:191
#define cmd_DeviceVerify
uint64_t micros64()
Definition: system.cpp:162
virtual void cork()=0
virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate)
Definition: RCOutput.h:145
#define cmd_DeviceReset
#define UDID_START
Definition: syscalls.c:216
#define CMD_READ_FLASH_ATM
virtual void serial_end(void)
Definition: RCOutput.h:164
virtual void write(uint8_t ch, uint16_t period_us)=0
float v
Definition: Printf.cpp:15
virtual void push()=0
#define SERIAL_4WAY_VERSION_LO
virtual int16_t read()=0
virtual void set_output_mode(uint16_t mask, enum output_mode mode)
Definition: RCOutput.h:180
#define cmd_DeviceInitFlash
#define cmd_DeviceWrite
#define FLIGHT_CONTROLLER_IDENTIFIER_LENGTH
Definition: msp_protocol.h:80
#define MSP_BOARD_INFO
Definition: msp_protocol.h:105
int32_t rpm
Definition: LogStructure.h:832
#define MSP_FC_VARIANT
Definition: msp_protocol.h:103
static AP_SerialManager * get_instance(void)
#define CMD_READ_FLASH_SIL
static void set_disabled_channel_mask(uint16_t mask)
Definition: SRV_Channel.h:426
#define ARDUPILOT_IDENTIFIER
Definition: msp_protocol.h:78
#define MSP_FC_VERSION
Definition: msp_protocol.h:104
#define MSP_REBOOT
Definition: msp_protocol.h:173
bool passed
Definition: location.cpp:17
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
#define CMD_ERASE_FLASH
float voltage
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
#define MSP_SET_MOTOR
Definition: msp_protocol.h:303
uint64_t time_us
Definition: LogStructure.h:831
#define MSP_UID
Definition: msp_protocol.h:326
uint8_t BL_WriteFlash(ioMem_t *pMem)
virtual bool serial_write_bytes(const uint8_t *bytes, uint16_t len)
Definition: RCOutput.h:151
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define cmd_InterfaceExit
#define SERIAL_4WAY_PROTOCOL_VER
#define cmd_DeviceEraseAll
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
#define cmd_Remote_Escape
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
#define RestartBootloader
uint32_t micros()
Definition: system.cpp:152
#define cmd_DeviceRead
#define CMD_SET_BUFFER
#define imARM_BLB
#define MSP_FEATURE_CONFIG
Definition: msp_protocol.h:120
#define AP_GROUPEND
Definition: AP_Param.h:121
#define ACK_I_VERIFY_ERROR
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define API_VERSION_MAJOR
Definition: msp_protocol.h:67
static void run_test()
Definition: INS_generic.cpp:98
virtual uint16_t serial_read_bytes(uint8_t *buf, uint16_t len)
Definition: RCOutput.h:157
#define API_VERSION_MINOR
Definition: msp_protocol.h:68
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
#define CMD_PROG_EEPROM
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
#define brSUCCESS
#define cmd_DevicePageErase