@@ -628,14 +628,6 @@ bool AP_BLHeli::BL_SendBuf(const uint8_t *buf, uint16_t len)
628
628
if (serial_start_ms == 0 ) {
629
629
serial_start_ms = AP_HAL::millis ();
630
630
}
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
- }
639
631
memcpy (blheli.buf , buf, len);
640
632
uint16_t crc = BL_CRC (buf, len);
641
633
blheli.buf [len] = crc;
@@ -750,18 +742,14 @@ bool AP_BLHeli::BL_ReadA(uint8_t cmd, uint8_t *buf, uint16_t n)
750
742
*/
751
743
bool AP_BLHeli::BL_ConnectEx (void )
752
744
{
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
- }
757
745
debug (" BL_ConnectEx %u/%u at %u" , blheli.chan , num_motors, motor_map[blheli.chan ]);
758
746
setDisconnected ();
759
747
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 };
760
748
if (!BL_SendBuf (BootInit, 21 )) {
761
749
return false ;
762
750
}
763
751
764
- uint8_t BootInfo[8 ];
752
+ uint8_t BootInfo[9 ];
765
753
if (!BL_ReadBuf (BootInfo, 8 )) {
766
754
return false ;
767
755
}
@@ -927,9 +915,13 @@ void AP_BLHeli::blheli_process_command(void)
927
915
switch (blheli.command ) {
928
916
case cmd_InterfaceTestAlive: {
929
917
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
+ }
933
925
}
934
926
uint8_t b = 0 ;
935
927
blheli_send_reply (&b, 1 );
@@ -1004,14 +996,28 @@ void AP_BLHeli::blheli_process_command(void)
1004
996
blheli_send_reply (&blheli.buf [0 ], 1 );
1005
997
break ;
1006
998
}
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));
999
+ // betaflight tries three times to connect, this avoids the need to wait some arbitrary
1000
+ // period for the interface to be up.
1001
+ bool failed = true ;
1002
+ for (uint8_t i = 0 ; i<3 ; i++) {
1003
+ blheli.chan = blheli.buf [0 ];
1004
+ blheli.ack = ACK_OK;
1005
+ if (BL_ConnectEx ()) {
1006
+ uint8_t buf[4 ] = {blheli.deviceInfo [blheli.chan ][0 ],
1007
+ blheli.deviceInfo [blheli.chan ][1 ],
1008
+ blheli.deviceInfo [blheli.chan ][2 ],
1009
+ blheli.deviceInfo [blheli.chan ][3 ]}; // device ID
1010
+ blheli_send_reply (buf, sizeof (buf));
1011
+ failed = false ;
1012
+ break ;
1013
+ }
1014
+ }
1015
+
1016
+ if (failed) {
1017
+ blheli.ack = ACK_D_GENERAL_ERROR;
1018
+ blheli_send_reply (&blheli.buf [0 ], 1 );
1019
+ setDisconnected ();
1020
+ }
1015
1021
break ;
1016
1022
}
1017
1023
0 commit comments