Copter: removed 1ms delay on startup
handled by GCS library now, not needed here
This commit is contained in:
parent
8511c2c04b
commit
a1797beb41
@ -20,15 +20,6 @@ static void failsafe_check_static()
|
|||||||
|
|
||||||
void Copter::init_ardupilot()
|
void Copter::init_ardupilot()
|
||||||
{
|
{
|
||||||
if (!hal.gpio->usb_connected()) {
|
|
||||||
// USB is not connected, this means UART0 may be a Xbee, with
|
|
||||||
// its darned bricking problem. We can't write to it for at
|
|
||||||
// least one second after powering up. Simplest solution for
|
|
||||||
// now is to delay for 1 second. Something more elegant may be
|
|
||||||
// added later
|
|
||||||
delay(1000);
|
|
||||||
}
|
|
||||||
|
|
||||||
// initialise serial port
|
// initialise serial port
|
||||||
serial_manager.init_console();
|
serial_manager.init_console();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user