mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Rover: use new HAL usb_connected() function
This commit is contained in:
parent
754bdbd25f
commit
481429de61
@ -305,10 +305,8 @@ AP_Mount camera_mount(¤t_loc, g_gps, &ahrs, 0);
|
|||||||
// Global variables
|
// Global variables
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
// APM2 only
|
// if USB is connected
|
||||||
#if USB_MUX_PIN > 0
|
|
||||||
static bool usb_connected;
|
static bool usb_connected;
|
||||||
#endif
|
|
||||||
|
|
||||||
/* Radio values
|
/* Radio values
|
||||||
Channel assignments
|
Channel assignments
|
||||||
|
@ -468,22 +468,13 @@ static bool telemetry_delayed(mavlink_channel_t chan)
|
|||||||
if (tnow > (uint32_t)g.telem_delay) {
|
if (tnow > (uint32_t)g.telem_delay) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#if USB_MUX_PIN > 0
|
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
||||||
if (chan == MAVLINK_COMM_0 && usb_connected) {
|
// this is USB telemetry, so won't be an Xbee
|
||||||
// this is an APM2 with USB telemetry
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
// we're either on the 2nd UART, or no USB cable is connected
|
// 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;
|
return true;
|
||||||
#else
|
|
||||||
if (chan == MAVLINK_COMM_0) {
|
|
||||||
// we're on the USB port
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
// don't send telemetry yet
|
|
||||||
return true;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -67,7 +67,6 @@
|
|||||||
# define LED_OFF LOW
|
# define LED_OFF LOW
|
||||||
# define SLIDE_SWITCH_PIN 40
|
# define SLIDE_SWITCH_PIN 40
|
||||||
# define PUSHBUTTON_PIN 41
|
# define PUSHBUTTON_PIN 41
|
||||||
# define USB_MUX_PIN -1
|
|
||||||
# define BATTERY_PIN_1 0
|
# define BATTERY_PIN_1 0
|
||||||
# define CURRENT_PIN_1 1
|
# define CURRENT_PIN_1 1
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
@ -82,7 +81,6 @@
|
|||||||
# define SLIDE_SWITCH_PIN (-1)
|
# define SLIDE_SWITCH_PIN (-1)
|
||||||
# define PUSHBUTTON_PIN (-1)
|
# define PUSHBUTTON_PIN (-1)
|
||||||
# define CLI_SLIDER_ENABLED DISABLED
|
# define CLI_SLIDER_ENABLED DISABLED
|
||||||
# define USB_MUX_PIN 23
|
|
||||||
# define BATTERY_PIN_1 1
|
# define BATTERY_PIN_1 1
|
||||||
# define CURRENT_PIN_1 2
|
# define CURRENT_PIN_1 2
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||||
@ -97,7 +95,6 @@
|
|||||||
# define SLIDE_SWITCH_PIN (-1)
|
# define SLIDE_SWITCH_PIN (-1)
|
||||||
# define PUSHBUTTON_PIN (-1)
|
# define PUSHBUTTON_PIN (-1)
|
||||||
# define CLI_SLIDER_ENABLED DISABLED
|
# define CLI_SLIDER_ENABLED DISABLED
|
||||||
# define USB_MUX_PIN -1
|
|
||||||
# define BATTERY_PIN_1 1
|
# define BATTERY_PIN_1 1
|
||||||
# define CURRENT_PIN_1 2
|
# define CURRENT_PIN_1 2
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
@ -112,7 +109,6 @@
|
|||||||
# define SLIDE_SWITCH_PIN (-1)
|
# define SLIDE_SWITCH_PIN (-1)
|
||||||
# define PUSHBUTTON_PIN (-1)
|
# define PUSHBUTTON_PIN (-1)
|
||||||
# define CLI_SLIDER_ENABLED DISABLED
|
# define CLI_SLIDER_ENABLED DISABLED
|
||||||
# define USB_MUX_PIN -1
|
|
||||||
# define BATTERY_PIN_1 -1
|
# define BATTERY_PIN_1 -1
|
||||||
# define CURRENT_PIN_1 -1
|
# define CURRENT_PIN_1 -1
|
||||||
#endif
|
#endif
|
||||||
|
@ -71,24 +71,6 @@ static void run_cli(AP_HAL::UARTDriver *port)
|
|||||||
|
|
||||||
static void init_ardupilot()
|
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);
|
|
||||||
|
|
||||||
usb_connected = !digitalRead(USB_MUX_PIN);
|
|
||||||
if (!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);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Console serial port
|
// Console serial port
|
||||||
//
|
//
|
||||||
// The console port buffers are defined to be sufficiently large to support
|
// The console port buffers are defined to be sufficiently large to support
|
||||||
@ -138,17 +120,16 @@ static void init_ardupilot()
|
|||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
|
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
|
||||||
|
|
||||||
#if USB_MUX_PIN > 0
|
usb_connected = hal.gpio->usb_connected();
|
||||||
if (!usb_connected) {
|
if (!usb_connected) {
|
||||||
// we are not connected via USB, re-init UART0 with right
|
// we are not connected via USB, re-init UART0 with right
|
||||||
// baud rate
|
// baud rate
|
||||||
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
|
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
// we have a 2nd serial port for telemetry
|
// we have a 2nd serial port for telemetry
|
||||||
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
hal.uartC->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
||||||
gcs3.init(hal.uartC);
|
gcs3.init(hal.uartC);
|
||||||
#endif
|
|
||||||
|
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
|
|
||||||
@ -235,9 +216,9 @@ static void init_ardupilot()
|
|||||||
#else
|
#else
|
||||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||||
cliSerial->println_P(msg);
|
cliSerial->println_P(msg);
|
||||||
#if USB_MUX_PIN == 0
|
if (gcs3.initialised) {
|
||||||
hal.uartC->println_P(msg);
|
hal.uartC->println_P(msg);
|
||||||
#endif
|
}
|
||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
|
|
||||||
startup_ground();
|
startup_ground();
|
||||||
@ -450,8 +431,7 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
|||||||
|
|
||||||
static void check_usb_mux(void)
|
static void check_usb_mux(void)
|
||||||
{
|
{
|
||||||
#if USB_MUX_PIN > 0
|
bool usb_check = hal.gpio->usb_connected();
|
||||||
bool usb_check = !digitalRead(USB_MUX_PIN);
|
|
||||||
if (usb_check == usb_connected) {
|
if (usb_check == usb_connected) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -459,11 +439,10 @@ static void check_usb_mux(void)
|
|||||||
// the user has switched to/from the telemetry port
|
// the user has switched to/from the telemetry port
|
||||||
usb_connected = usb_check;
|
usb_connected = usb_check;
|
||||||
if (usb_connected) {
|
if (usb_connected) {
|
||||||
hal.uartA->begin(SERIAL0_BAUD, 128, 128);
|
hal.uartA->begin(SERIAL0_BAUD);
|
||||||
} else {
|
} else {
|
||||||
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD), 128, 128);
|
hal.uartA->begin(map_baudrate(g.serial3_baud, SERIAL3_BAUD));
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user