mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: use new usb_connected() HAL function
This commit is contained in:
parent
4bd6b2f428
commit
754bdbd25f
@ -1292,9 +1292,7 @@ static void slow_loop()
|
||||
if(g.radio_tuning > 0)
|
||||
tuning();
|
||||
|
||||
#if USB_MUX_PIN > 0
|
||||
check_usb_mux();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -488,25 +488,16 @@ static void NOINLINE send_statustext(mavlink_channel_t chan)
|
||||
static bool telemetry_delayed(mavlink_channel_t chan)
|
||||
{
|
||||
uint32_t tnow = millis() >> 10;
|
||||
if (tnow > (uint8_t)g.telem_delay) {
|
||||
if (tnow > (uint32_t)g.telem_delay) {
|
||||
return false;
|
||||
}
|
||||
#if USB_MUX_PIN > 0
|
||||
if (chan == MAVLINK_COMM_0 && ap_system.usb_connected) {
|
||||
// this is an APM2 with USB telemetry
|
||||
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
||||
// this is USB telemetry, so won't be an Xbee
|
||||
return false;
|
||||
}
|
||||
// we're either on the 2nd UART, or no USB cable is connected
|
||||
// we need to delay telemetry
|
||||
// we need to delay telemetry by the TELEM_DELAY time
|
||||
return true;
|
||||
#else
|
||||
if (chan == MAVLINK_COMM_0) {
|
||||
// we're on the USB port
|
||||
return false;
|
||||
}
|
||||
// don't send telemetry yet
|
||||
return true;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -2168,9 +2159,7 @@ static void mavlink_delay_cb()
|
||||
last_5s = tnow;
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Initialising APM..."));
|
||||
}
|
||||
#if USB_MUX_PIN > 0
|
||||
check_usb_mux();
|
||||
#endif
|
||||
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
@ -171,28 +171,24 @@
|
||||
# define LED_ON HIGH
|
||||
# define LED_OFF LOW
|
||||
# define PUSHBUTTON_PIN 41
|
||||
# define USB_MUX_PIN -1
|
||||
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0
|
||||
# define BATTERY_CURR_PIN 1 // Battery current on A1
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define USB_MUX_PIN 23
|
||||
# define BATTERY_VOLT_PIN 1 // Battery voltage on A1
|
||||
# define BATTERY_CURR_PIN 2 // Battery current on A2
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define USB_MUX_PIN -1
|
||||
# define BATTERY_VOLT_PIN 1 // Battery voltage on A1
|
||||
# define BATTERY_CURR_PIN 2 // Battery current on A2
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define USB_MUX_PIN -1
|
||||
# define BATTERY_VOLT_PIN -1
|
||||
# define BATTERY_CURR_PIN -1
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SMACCM
|
||||
@ -200,7 +196,6 @@
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define USB_MUX_PIN -1
|
||||
# define BATTERY_VOLT_PIN -1
|
||||
# define BATTERY_CURR_PIN -1
|
||||
#endif
|
||||
|
@ -75,14 +75,7 @@ static void run_cli(AP_HAL::UARTDriver *port)
|
||||
|
||||
static void init_ardupilot()
|
||||
{
|
||||
#if USB_MUX_PIN > 0
|
||||
// on the APM2 board we have a mux thet switches UART0 between
|
||||
// USB and the board header. If the right ArduPPM firmware is
|
||||
// installed we can detect if USB is connected using the
|
||||
// USB_MUX_PIN
|
||||
pinMode(USB_MUX_PIN, INPUT);
|
||||
|
||||
ap_system.usb_connected = !digitalRead(USB_MUX_PIN);
|
||||
ap_system.usb_connected = hal.gpio->usb_connected();
|
||||
if (!ap_system.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
|
||||
@ -91,7 +84,6 @@ static void init_ardupilot()
|
||||
// added later
|
||||
delay(1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Console serial port
|
||||
//
|
||||
@ -144,14 +136,17 @@ static void init_ardupilot()
|
||||
// hal.scheduler->delay.
|
||||
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
|
||||
|
||||
#if USB_MUX_PIN > 0
|
||||
ap_system.usb_connected = hal.gpio->usb_connected();
|
||||
if (!ap_system.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));
|
||||
}
|
||||
#else
|
||||
// we have a 2nd serial port for telemetry
|
||||
|
||||
#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
|
||||
// a MUX is used
|
||||
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
||||
gcs3.init(hal.uartC);
|
||||
#endif
|
||||
@ -216,9 +211,9 @@ static void init_ardupilot()
|
||||
#if CLI_ENABLED == ENABLED
|
||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||
cliSerial->println_P(msg);
|
||||
#if USB_MUX_PIN == 0
|
||||
if (gcs3.initialised) {
|
||||
hal.uartC->println_P(msg);
|
||||
#endif
|
||||
}
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
@ -549,10 +544,9 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
||||
return default_baud;
|
||||
}
|
||||
|
||||
#if USB_MUX_PIN > 0
|
||||
static void check_usb_mux(void)
|
||||
{
|
||||
bool usb_check = !digitalRead(USB_MUX_PIN);
|
||||
bool usb_check = hal.gpio->usb_connected();
|
||||
if (usb_check == ap_system.usb_connected) {
|
||||
return;
|
||||
}
|
||||
@ -565,7 +559,6 @@ static void check_usb_mux(void)
|
||||
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* called by gyro/accel init to flash LEDs so user
|
||||
|
Loading…
Reference in New Issue
Block a user