26 #if HAL_SUPPORT_RCOUT_SERIAL 37 #define debug(fmt, args ...) do { if (debug_level) { gcs().send_text(MAV_SEVERITY_INFO, "ESC: " fmt, ## args); } } while (0) 41 #define BLHELI_UART_LOCK_KEY 0x20180402 51 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) 101 AP_BLHeli::AP_BLHeli(
void)
110 bool AP_BLHeli::msp_process_byte(uint8_t c)
112 if (msp.state == MSP_IDLE) {
113 msp.escMode = PROTOCOL_NONE;
115 msp.state = MSP_HEADER_START;
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;
125 msp.packetType = MSP_PACKET_COMMAND;
126 msp.state = MSP_HEADER_ARROW;
129 msp.packetType = MSP_PACKET_REPLY;
130 msp.state = MSP_HEADER_ARROW;
135 }
else if (msp.state == MSP_HEADER_ARROW) {
136 if (c >
sizeof(msp.buf)) {
137 msp.state = MSP_IDLE;
143 msp.state = MSP_HEADER_SIZE;
145 }
else if (msp.state == MSP_HEADER_SIZE) {
148 msp.state = MSP_HEADER_CMD;
149 }
else if (msp.state == MSP_HEADER_CMD && msp.offset < msp.dataSize) {
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;
156 msp.state = MSP_IDLE;
165 void AP_BLHeli::blheli_crc_update(uint8_t c)
173 bool AP_BLHeli::blheli_4way_process_byte(uint8_t c)
175 if (blheli.state == BLHELI_IDLE) {
177 blheli.state = BLHELI_HEADER_START;
179 blheli_crc_update(c);
183 }
else if (blheli.state == BLHELI_HEADER_START) {
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) {
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;
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;
206 }
else if (blheli.state == BLHELI_CRC1) {
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;
214 blheli.state = BLHELI_IDLE;
223 void AP_BLHeli::msp_send_reply(uint8_t cmd,
const uint8_t *buf, uint8_t len)
225 uint8_t *b = &msp.buf[0];
234 for (uint8_t i=0; i<len+2; i++) {
238 uart->write_locked(&msp.buf[0], len+6, BLHELI_UART_LOCK_KEY);
241 void AP_BLHeli::putU16(uint8_t *b, uint16_t
v)
247 uint16_t AP_BLHeli::getU16(
const uint8_t *b)
249 return b[0] | (b[1]<<8);
252 void AP_BLHeli::putU32(uint8_t *b, uint32_t
v)
260 void AP_BLHeli::putU16_BE(uint8_t *b, uint16_t
v)
269 void AP_BLHeli::msp_process_command(
void)
271 debug(
"MSP cmd %u len=%u", msp.cmdMSP, msp.dataSize);
272 switch (msp.cmdMSP) {
274 debug(
"MSP_API_VERSION");
276 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
281 debug(
"MSP_FC_VARIANT");
286 debug(
"MSP_FC_VERSION");
287 uint8_t version[3] = { 3, 3, 0 };
288 msp_send_reply(msp.cmdMSP, version,
sizeof(version));
292 debug(
"MSP_BOARD_INFO");
294 uint8_t buf[7] = {
'A',
'R',
'C',
'H', 0, 0, 0 };
295 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
300 debug(
"MSP_BUILD_INFO");
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));
311 debug(
"MSP: ignoring reboot command");
317 msp_send_reply(msp.cmdMSP, (
const uint8_t *)
UDID_START, 12);
321 debug(
"MSP_ADVANCED_CONFIG");
326 buf[3] = (uint8_t)PWM_TYPE_DSHOT150;
327 putU16(&buf[4], 480);
328 putU16(&buf[6], 450);
331 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
336 debug(
"MSP_FEATURE_CONFIG");
339 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
346 putU16(&buf[0], 1000);
348 putU16(&buf[4], 0x27);
356 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
361 debug(
"MSP_MOTOR_3D_CONFIG");
363 putU16(&buf[0], 1406);
364 putU16(&buf[2], 1514);
365 putU16(&buf[4], 1460);
366 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
371 debug(
"MSP_MOTOR_CONFIG");
372 uint16_t min_pwm = 1000;
373 uint16_t max_pwm = 2000;
376 putU16(&buf[0], min_pwm+30);
377 putU16(&buf[2], max_pwm);
378 putU16(&buf[4], min_pwm);
379 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
387 uint16_t min_pwm = 1000;
388 uint16_t max_pwm = 2000;
390 for (uint8_t i = 0; i < num_motors; i++) {
392 putU16(&buf[2*i], v);
394 msp_send_reply(msp.cmdMSP, buf,
sizeof(buf));
399 debug(
"MSP_SET_MOTOR");
401 uint8_t nmotors = msp.dataSize / 2;
402 debug(
"MSP_SET_MOTOR %u", nmotors);
404 motors_disabled =
true;
406 for (uint8_t i = 0; i < nmotors; i++) {
407 if (i >= num_motors) {
410 uint16_t
v = getU16(&msp.buf[i*2]);
411 debug(
"MSP_SET_MOTOR %u %u", i, v);
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];
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) {
437 msp_send_reply(msp.cmdMSP, &n, 1);
441 debug(
"Unknown MSP command %u", msp.cmdMSP);
450 void AP_BLHeli::blheli_send_reply(
const uint8_t *buf, uint16_t len)
452 uint8_t *b = &blheli.buf[0];
454 *b++ = blheli.command;
455 putU16_BE(b, blheli.address); b += 2;
456 *b++ = len==256?0:len;
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);
468 uint16_t AP_BLHeli::BL_CRC(
const uint8_t *buf, uint16_t len)
473 for (uint8_t i = 0; i < 8; i++) {
474 if (((xb & 0x01) ^ (crc & 0x0001)) !=0 ) {
488 return blheli.deviceInfo[0] > 0;
491 void AP_BLHeli::setDisconnected(
void)
493 blheli.deviceInfo[0] = 0;
494 blheli.deviceInfo[1] = 0;
500 bool AP_BLHeli::BL_SendBuf(
const uint8_t *buf, uint16_t len)
503 if (blheli.chan >= num_motors) {
510 if (serial_start_ms == 0) {
514 if (serial_start_ms == 0 || now - serial_start_ms < 1000) {
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;
537 bool AP_BLHeli::BL_ReadBuf(uint8_t *buf, uint16_t len)
540 uint16_t req_bytes = len+(check_crc?3:1);
542 debug(
"BL_ReadBuf %u -> %u", len, n);
543 if (req_bytes != n) {
549 uint16_t crc = BL_CRC(blheli.buf, len);
550 if ((crc & 0xff) != blheli.buf[len] ||
551 (crc >> 8) != blheli.buf[len+1]) {
557 debug(
"bad ACK 0x%02x", blheli.buf[len+2]);
563 debug(
"bad ACK1 0x%02x", blheli.buf[len]);
569 memcpy(buf, blheli.buf, len);
574 uint8_t AP_BLHeli::BL_GetACK(uint16_t timeout_ms)
587 bool AP_BLHeli::BL_SendCMDSetAddress()
590 if (blheli.address == 0xFFFF) {
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)) {
601 bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)
603 if (BL_SendCMDSetAddress()) {
604 uint8_t sCMD[] = {cmd, uint8_t(n==256?0:n)};
605 if (!BL_SendBuf(sCMD, 2)) {
608 return BL_ReadBuf(buf, n);
618 debug(
"BL_ConnectEx %u/%u at %u", blheli.chan, num_motors, motor_map[blheli.chan]);
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)) {
626 if (!BL_ReadBuf(BootInfo, 8)) {
631 if (strncmp((
const char *)BootInfo,
"471", 3) != 0) {
637 blheli.deviceInfo[2] = BootInfo[3];
638 blheli.deviceInfo[1] = BootInfo[4];
639 blheli.deviceInfo[0] = BootInfo[5];
641 blheli.interface_mode = 0;
643 uint16_t *devword = (uint16_t *)blheli.deviceInfo;
650 debug(
"Interface type imATM_BLB");
660 debug(
"Interface type imSIL_BLB");
667 debug(
"Interface type imARM_BLB");
671 debug(
"Unknown interface type 0x%04x", *devword);
674 blheli.deviceInfo[3] = blheli.interface_mode;
681 if (!BL_SendBuf(sCMD, 2)) {
692 if (BL_SendCMDSetAddress()) {
694 if (!BL_SendBuf(sCMD, 2)) {
705 blheli.deviceInfo[0] = 1;
709 uint8_t AP_BLHeli::BL_SendCMDSetBuffer(
const uint8_t *buf, uint16_t nbytes)
711 uint8_t sCMD[] = {
CMD_SET_BUFFER, 0, uint8_t(nbytes>>8), uint8_t(nbytes&0xff)};
712 if (!BL_SendBuf(sCMD, 4)) {
716 if ((ack = BL_GetACK()) !=
brNONE) {
717 debug(
"BL_SendCMDSetBuffer ack failed 0x%02x", ack);
721 if (!BL_SendBuf(buf, nbytes)) {
722 debug(
"BL_SendCMDSetBuffer send failed");
729 bool AP_BLHeli::BL_WriteA(uint8_t cmd,
const uint8_t *buf, uint16_t nbytes, uint32_t timeout_ms)
731 if (BL_SendCMDSetAddress()) {
732 if (!BL_SendCMDSetBuffer(buf, nbytes)) {
736 uint8_t sCMD[] = {cmd, 0x01};
737 if (!BL_SendBuf(sCMD, 2)) {
740 return (BL_GetACK(timeout_ms) ==
brSUCCESS);
753 if (BL_SendCMDSetAddress()) {
754 if (!BL_SendCMDSetBuffer(buf, n)) {
758 if (!BL_SendBuf(sCMD, 2)) {
761 uint8_t ack = BL_GetACK(40);
781 void AP_BLHeli::blheli_process_command(
void)
783 debug(
"BLHeli cmd 0x%02x len=%u", blheli.command, blheli.param_len);
785 switch (blheli.command) {
787 debug(
"cmd_InterfaceTestAlive");
789 if (blheli.ack !=
ACK_OK) {
793 blheli_send_reply(&b, 1);
797 debug(
"cmd_ProtocolGetVersion");
800 blheli_send_reply(buf,
sizeof(buf));
804 debug(
"cmd_InterfaceGetName");
805 uint8_t buf[5] = { 4,
'A',
'R',
'D',
'U' };
806 blheli_send_reply(buf,
sizeof(buf));
810 debug(
"cmd_InterfaceGetVersion");
812 blheli_send_reply(buf,
sizeof(buf));
816 debug(
"cmd_InterfaceExit");
817 msp.escMode = PROTOCOL_NONE;
819 blheli_send_reply(&b, 1);
822 if (motors_disabled) {
823 motors_disabled =
false;
827 debug(
"Unlocked UART");
834 debug(
"cmd_DeviceReset(%u)",
unsigned(blheli.buf[0]));
835 blheli.chan = blheli.buf[0];
836 switch (blheli.interface_mode) {
845 blheli_send_reply(&blheli.chan, 1);
851 debug(
"cmd_DeviceInitFlash(%u)",
unsigned(blheli.buf[0]));
852 blheli.chan = blheli.buf[0];
853 for (uint8_t tries=0; tries<5; tries++) {
860 uint8_t buf[4] = {blheli.deviceInfo[0],
861 blheli.deviceInfo[1],
862 blheli.deviceInfo[2],
863 blheli.deviceInfo[3]};
864 blheli_send_reply(buf,
sizeof(buf));
869 debug(
"cmd_InterfaceSetMode(%u)",
unsigned(blheli.buf[0]));
870 blheli.interface_mode = blheli.buf[0];
871 blheli_send_reply(&blheli.interface_mode, 1);
876 uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
877 debug(
"cmd_DeviceRead(%u) n=%u", blheli.chan, nbytes);
880 if (!BL_ReadA(cmd, buf, nbytes)) {
883 blheli_send_reply(buf, nbytes);
888 uint8_t page = blheli.buf[0];
889 debug(
"cmd_DevicePageErase(%u) im=%u", page, blheli.interface_mode);
890 switch (blheli.interface_mode) {
893 if (blheli.interface_mode ==
imARM_BLB) {
895 blheli.address = page << 10;
898 blheli.address = page << 9;
900 debug(
"ARM PageErase 0x%04x", blheli.address);
903 blheli_send_reply(&page, 1);
908 blheli_send_reply(&page, 1);
915 uint16_t nbytes = blheli.param_len;
916 debug(
"cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode);
918 memcpy(buf, blheli.buf, nbytes);
919 switch (blheli.interface_mode) {
927 debug(
"Unsupported flash mode imSK");
932 blheli_send_reply(&b, 1);
937 uint16_t nbytes = blheli.param_len;
938 debug(
"cmd_DeviceWrite n=%u im=%u", nbytes, blheli.interface_mode);
939 switch (blheli.interface_mode) {
942 memcpy(buf, blheli.buf, nbytes);
951 blheli_send_reply(&b, 1);
956 uint16_t nbytes = blheli.buf[0]?blheli.buf[0]:256;
958 debug(
"cmd_DeviceReadEEprom n=%u im=%u", nbytes, blheli.interface_mode);
959 switch (blheli.interface_mode) {
970 if (blheli.ack !=
ACK_OK) {
974 blheli_send_reply(buf, nbytes);
979 uint16_t nbytes = blheli.param_len;
981 memcpy(buf, blheli.buf, nbytes);
982 debug(
"cmd_DeviceWriteEEprom n=%u im=%u", nbytes, blheli.interface_mode);
983 switch (blheli.interface_mode) {
992 blheli_send_reply(&b, 1);
1001 debug(
"Unknown BLHeli protocol 0x%02x", blheli.command);
1003 blheli_send_reply(&b, 1);
1012 bool AP_BLHeli::process_input(uint8_t b)
1014 bool valid_packet =
false;
1016 if (msp.escMode == PROTOCOL_4WAY && blheli.state == BLHELI_IDLE && b ==
'$') {
1017 debug(
"Change to MSP mode");
1018 msp.escMode = PROTOCOL_NONE;
1020 serial_start_ms = 0;
1022 if (msp.escMode != PROTOCOL_4WAY && msp.state == MSP_IDLE && b ==
'/') {
1023 debug(
"Change to BLHeli mode");
1024 msp.escMode = PROTOCOL_4WAY;
1026 if (msp.escMode == PROTOCOL_4WAY) {
1027 blheli_4way_process_byte(b);
1029 msp_process_byte(b);
1031 if (msp.escMode == PROTOCOL_4WAY) {
1032 if (blheli.state == BLHELI_COMMAND_RECEIVED) {
1033 valid_packet =
true;
1035 if (uart->lock_port(BLHELI_UART_LOCK_KEY)) {
1038 blheli_process_command();
1039 blheli.state = BLHELI_IDLE;
1040 msp.state = MSP_IDLE;
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)) {
1049 msp_process_command();
1051 msp.state = MSP_IDLE;
1052 blheli.state = BLHELI_IDLE;
1055 return valid_packet;
1068 return process_input(b);
1076 void AP_BLHeli::run_connection_test(uint8_t
chan)
1079 uint8_t saved_chan = blheli.chan;
1081 debug(
"Running test on channel %u", blheli.chan);
1084 for (uint8_t tries=0; tries<5; tries++) {
1091 blheli.address = blheli.interface_mode==
imATM_BLB?0:0x7c00;
1092 passed &= BL_ReadA(cmd, buf,
sizeof(buf));
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;
1110 void AP_BLHeli::update(
void)
1115 AP_HAL::millis() - last_valid_ms > uint32_t(timeout_sec.get())*1000U) {
1118 if (serial_start_ms) {
1120 serial_start_ms = 0;
1122 if (motors_disabled) {
1123 motors_disabled =
false;
1126 debug(
"Unlocked UART");
1128 uart_locked =
false;
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);
1140 if (
gcs().install_alternative_protocol(MAVLINK_COMM_0,
1143 debug(
"BLHeli installed");
1146 uint16_t mask = uint16_t(channel_mask.get());
1182 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) 1186 if (channel_auto.get() == 1) {
1195 for (uint8_t i=0; i<16 && num_motors < max_motors; i++) {
1196 if (mask & (1U<<i)) {
1197 motor_map[num_motors] = i;
1201 debug(
"ESC: %u motors mask=0x%04x", num_motors, mask);
1203 if (telem_rate > 0) {
1205 if (serial_manager) {
1215 uint8_t AP_BLHeli::telem_crc8(uint8_t crc, uint8_t crc_seed)
const 1217 uint8_t crc_u = crc;
1220 for (uint8_t i=0; i<8; i++) {
1221 crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
1230 void AP_BLHeli::read_telemetry_packet(
void)
1232 uint8_t buf[telem_packet_size];
1234 for (uint8_t i=0; i<telem_packet_size; i++) {
1235 int16_t v = telem_uart->
read();
1240 buf[i] = uint8_t(v);
1244 for (uint8_t i=0; i<telem_packet_size-1; i++) {
1245 crc = telem_crc8(buf[i], crc);
1248 if (buf[telem_packet_size-1] != crc) {
1250 debug(
"Bad CRC on %u\n", last_telem_esc);
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];
1264 rpm : int32_t(rpm*100U),
1273 hal.
console->
printf(
"ESC[%u] T=%u V=%u C=%u con=%u RPM=%u\n",
1287 void AP_BLHeli::update_telemetry(
void)
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) {
1297 telem_rate_us = 2000;
1300 if (nbytes > telem_packet_size) {
1303 if (nbytes > telem_packet_size*2) {
1306 telem_uart =
nullptr;
1315 nbytes < telem_packet_size &&
1316 now - last_telem_request_us < telem_rate_us) {
1320 if (nbytes > 0 && nbytes < telem_packet_size) {
1327 if (nbytes == telem_packet_size) {
1329 read_telemetry_packet();
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];
1335 last_telem_request_us = now;
1339 #endif // HAL_SUPPORT_RCOUT_SERIAL bool get_soft_armed() const
uint8_t BL_VerifyFlash(ioMem_t *pMem)
static AP_SerialManager serial_manager
#define cmd_InterfaceGetName
uint16_t crc_xmodem(const uint8_t *data, uint16_t len)
#define ACK_D_GENERAL_ERROR
#define MSP_PROTOCOL_VERSION
#define cmd_InterfaceSetMode
bool logging_enabled() const
virtual uint16_t read(uint8_t ch)=0
AP_HAL::UARTDriver * console
#define MSP_ADVANCED_CONFIG
Interface definition for the various Ground Control System.
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data)
#define cmd_DeviceWriteEEprom
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define cmd_DeviceC2CK_LOW
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
#define SERIAL_4WAY_VERSION_HI
void WriteBlock(const void *pBuffer, uint16_t size)
#define ACK_I_INVALID_CMD
static AP_Motors * get_instance(void)
#define cmd_InterfaceTestAlive
bool isMcuConnected(void)
#define debug(fmt, args ...)
uint8_t BL_SendCMDKeepAlive(void)
AP_MotorsMatrix motors(400)
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
#define MSP_MOTOR_3D_CONFIG
#define cmd_ProtocolGetVersion
#define cmd_InterfaceGetVersion
#define cmd_DeviceReadEEprom
virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm)
uint8_t BL_PageErase(ioMem_t *pMem)
virtual uint16_t get_motor_mask()=0
#define CMD_VERIFY_FLASH_ARM
static DataFlash_Class * instance(void)
virtual void set_telem_request_mask(uint16_t mask)
virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate)
#define CMD_READ_FLASH_ATM
virtual void serial_end(void)
virtual void write(uint8_t ch, uint16_t period_us)=0
#define SERIAL_4WAY_VERSION_LO
virtual void set_output_mode(uint16_t mask, enum output_mode mode)
#define cmd_DeviceInitFlash
#define FLIGHT_CONTROLLER_IDENTIFIER_LENGTH
static AP_SerialManager * get_instance(void)
#define CMD_READ_FLASH_SIL
static void set_disabled_channel_mask(uint16_t mask)
#define ARDUPILOT_IDENTIFIER
AP_HAL::AnalogSource * chan
uint8_t BL_WriteFlash(ioMem_t *pMem)
virtual bool serial_write_bytes(const uint8_t *bytes, uint16_t len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#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)
#define RestartBootloader
#define MSP_FEATURE_CONFIG
#define ACK_I_VERIFY_ERROR
AP_HAL::Scheduler * scheduler
#define API_VERSION_MAJOR
virtual uint16_t serial_read_bytes(uint8_t *buf, uint16_t len)
#define API_VERSION_MINOR
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
#define cmd_DevicePageErase