Copter: setup uart after checking usb_connected

This commit is contained in:
Randy Mackay 2015-01-28 12:38:55 +09:00 committed by Andrew Tridgell
parent 0a195671b3
commit e0cfe091fb

View File

@ -126,9 +126,6 @@ static void init_ardupilot()
barometer.init();
// init the GCS connected to the console
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console);
// Register the mavlink service callback. This will run
// anytime there are more than 5ms remaining in a call to
// hal.scheduler->delay.
@ -139,6 +136,9 @@ static void init_ardupilot()
ap.usb_connected = true;
check_usb_mux();
// init the GCS connected to the console
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console);
#if CONFIG_HAL_BOARD != HAL_BOARD_APM2
// we have a 2nd serial port for telemetry on all boards except
// APM2. We actually do have one on APM2 but it isn't necessary as
@ -403,7 +403,7 @@ static void check_usb_mux(void)
// between USB and a TTL serial connection. When on USB we use
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
// at SERIAL1_BAUD.
if (usb_connected) {
if (ap.usb_connected) {
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console);
} else {
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink1);