AntennaTracker: fixed APM2 serial speed handling

need to change based on USB mux status
This commit is contained in:
Andrew Tridgell 2014-03-22 19:31:28 +11:00
parent 3a3a074fab
commit af2ae30b65
2 changed files with 30 additions and 0 deletions

View File

@ -108,6 +108,8 @@ static struct {
static uint32_t start_time_ms;
static bool usb_connected;
////////////////////////////////////////////////////////////////////////////////
// prototypes
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
@ -216,6 +218,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ compass_accumulate, 1, 1500 },
{ barometer_accumulate, 1, 900 },
{ update_notify, 1, 100 },
{ check_usb_mux, 5, 300 },
{ gcs_retry_deferred, 1, 1000 },
{ one_second_loop, 50, 3900 }
};

View File

@ -27,6 +27,11 @@ static void init_tracker()
// more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
// 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.serial1_baud, SERIAL1_BAUD),
128, SERIAL1_BUFSIZE);
@ -235,3 +240,25 @@ static void set_mode(enum ControlMode mode)
}
}
static void check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
if (usb_check == usb_connected) {
return;
}
// 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 SERIAL1_BAUD.
if (usb_connected) {
hal.uartA->begin(SERIAL0_BAUD);
} else {
hal.uartA->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD));
}
#endif
}