Skip to content

Commit af95ed5

Browse files
andyp1pertridge
authored andcommitted
AP_BLHeli: properly deal with interface test when disconnected
don't cache connection result and return appropriate error if connection fails. don't wait 1s to send first serial passthrough message retry failed cmd_DeviceInitFlash as per betaflight ensure the bootinfo structure is large enough
1 parent 9e88953 commit af95ed5

File tree

1 file changed

+33
-25
lines changed

1 file changed

+33
-25
lines changed

libraries/AP_BLHeli/AP_BLHeli.cpp

Lines changed: 33 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -628,14 +628,6 @@ bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)
628628
if (serial_start_ms == 0) {
629629
serial_start_ms = AP_HAL::millis();
630630
}
631-
uint32_t now = AP_HAL::millis();
632-
if (serial_start_ms == 0 || now - serial_start_ms < 1000) {
633-
/*
634-
we've just started the interface. We want it idle for at
635-
least 1 second before we start sending serial data.
636-
*/
637-
hal.scheduler->delay(1100);
638-
}
639631
memcpy(blheli.buf, buf, len);
640632
uint16_t crc = BL_CRC(buf, len);
641633
blheli.buf[len] = crc;
@@ -750,18 +742,14 @@ bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)
750742
*/
751743
bool AP_BLHeli::BL_ConnectEx(void)
752744
{
753-
if (blheli.connected[blheli.chan] != 0) {
754-
debug("Using cached interface 0x%x for %u", blheli.interface_mode[blheli.chan], blheli.chan);
755-
return true;
756-
}
757745
debug("BL_ConnectEx %u/%u at %u", blheli.chan, num_motors, motor_map[blheli.chan]);
758746
setDisconnected();
759747
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};
760748
if (!BL_SendBuf(BootInit, 21)) {
761749
return false;
762750
}
763751

764-
uint8_t BootInfo[8];
752+
uint8_t BootInfo[9];
765753
if (!BL_ReadBuf(BootInfo, 8)) {
766754
return false;
767755
}
@@ -927,9 +915,13 @@ void AP_BLHeli::blheli_process_command(void)
927915
switch (blheli.command) {
928916
case cmd_InterfaceTestAlive: {
929917
debug("cmd_InterfaceTestAlive");
930-
BL_SendCMDKeepAlive();
931-
if (blheli.ack != ACK_OK) {
932-
setDisconnected();
918+
if (!isMcuConnected()) {
919+
blheli.ack = ACK_D_GENERAL_ERROR;
920+
} else {
921+
BL_SendCMDKeepAlive();
922+
if (blheli.ack != ACK_OK) {
923+
setDisconnected();
924+
}
933925
}
934926
uint8_t b = 0;
935927
blheli_send_reply(&b, 1);
@@ -997,21 +989,37 @@ void AP_BLHeli::blheli_process_command(void)
997989
}
998990

999991
case cmd_DeviceInitFlash: {
992+
uint8_t chan = blheli.buf[0];
993+
1000994
debug("cmd_DeviceInitFlash(%u)", unsigned(blheli.buf[0]));
1001995
if (blheli.buf[0] >= num_motors) {
1002996
debug("bad channel %u", blheli.buf[0]);
1003997
blheli.ack = ACK_I_INVALID_CHANNEL;
1004-
blheli_send_reply(&blheli.buf[0], 1);
998+
blheli_send_reply(&chan, 1);
1005999
break;
10061000
}
1007-
blheli.chan = blheli.buf[0];
1008-
blheli.ack = ACK_OK;
1009-
BL_ConnectEx();
1010-
uint8_t buf[4] = {blheli.deviceInfo[blheli.chan][0],
1011-
blheli.deviceInfo[blheli.chan][1],
1012-
blheli.deviceInfo[blheli.chan][2],
1013-
blheli.deviceInfo[blheli.chan][3]}; // device ID
1014-
blheli_send_reply(buf, sizeof(buf));
1001+
// betaflight tries three times to connect, this avoids the need to wait some arbitrary
1002+
// period for the interface to be up.
1003+
bool failed = true;
1004+
for (uint8_t i = 0; i<3; i++) {
1005+
blheli.chan = chan;
1006+
blheli.ack = ACK_OK;
1007+
if (BL_ConnectEx()) {
1008+
uint8_t buf[4] = {blheli.deviceInfo[blheli.chan][0],
1009+
blheli.deviceInfo[blheli.chan][1],
1010+
blheli.deviceInfo[blheli.chan][2],
1011+
blheli.deviceInfo[blheli.chan][3]}; // device ID
1012+
blheli_send_reply(buf, sizeof(buf));
1013+
failed = false;
1014+
break;
1015+
}
1016+
}
1017+
1018+
if (failed) {
1019+
blheli.ack = ACK_D_GENERAL_ERROR;
1020+
blheli_send_reply(&chan, 1);
1021+
setDisconnected();
1022+
}
10151023
break;
10161024
}
10171025

0 commit comments

Comments
 (0)