|
|
|
@ -120,12 +120,10 @@ static void init_ardupilot()
@@ -120,12 +120,10 @@ static void init_ardupilot()
|
|
|
|
|
// more than 5ms remaining in your call to hal.scheduler->delay |
|
|
|
|
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5); |
|
|
|
|
|
|
|
|
|
usb_connected = hal.gpio->usb_connected(); |
|
|
|
|
if (!usb_connected) { |
|
|
|
|
// we are not connected via USB, re-init UART0 with right |
|
|
|
|
// baud rate |
|
|
|
|
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); |
|
|
|
|
} |
|
|
|
|
// we start by assuming USB connected, as we initialed the serial |
|
|
|
|
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be. |
|
|
|
|
usb_connected = true; |
|
|
|
|
check_usb_mux(); |
|
|
|
|
|
|
|
|
|
// we have a 2nd serial port for telemetry |
|
|
|
|
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128); |
|
|
|
@ -429,15 +427,21 @@ static void check_usb_mux(void)
@@ -429,15 +427,21 @@ static void check_usb_mux(void)
|
|
|
|
|
|
|
|
|
|
// the user has switched to/from the telemetry port |
|
|
|
|
usb_connected = usb_check; |
|
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 |
|
|
|
|
// the APM2 has a MUX setup where the first serial port switches |
|
|
|
|
// 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 SERIAL3_BAUD. |
|
|
|
|
if (usb_connected) { |
|
|
|
|
hal.uartA->begin(SERIAL0_BAUD); |
|
|
|
|
} else { |
|
|
|
|
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD)); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/* |
|
|
|
|
* Read board voltage in millivolts |
|
|
|
|
*/ |
|
|
|
|