mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
HAL_ChibiOS: fixed stdout in early startup bug
this caused a failure to boot on some boards if they tried to print messages in early startup code before hal was initialised thanks to @Shadowru for reporting the issue
This commit is contained in:
parent
b1742b4e19
commit
e8ab35a192
@ -279,8 +279,8 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
|
|||||||
* RTOS is active.
|
* RTOS is active.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifdef HAL_USB_PRODUCT_ID
|
#if HAL_USE_SERIAL_USB == TRUE
|
||||||
setup_usb_strings();
|
usb_initialise();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_STDOUT_SERIAL
|
#ifdef HAL_STDOUT_SERIAL
|
||||||
|
@ -1446,4 +1446,35 @@ uint8_t UARTDriver::get_options(void) const
|
|||||||
return _last_options;
|
return _last_options;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_USE_SERIAL_USB == TRUE
|
||||||
|
/*
|
||||||
|
initialise the USB bus, called from both UARTDriver and stdio for startup debug
|
||||||
|
This can be called before the hal is initialised so must not call any hal functions
|
||||||
|
*/
|
||||||
|
void usb_initialise(void)
|
||||||
|
{
|
||||||
|
static bool initialised;
|
||||||
|
if (initialised) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
initialised = true;
|
||||||
|
setup_usb_strings();
|
||||||
|
sduObjectInit(&SDU1);
|
||||||
|
sduStart(&SDU1, &serusbcfg1);
|
||||||
|
#if HAL_HAVE_DUAL_USB_CDC
|
||||||
|
sduObjectInit(&SDU2);
|
||||||
|
sduStart(&SDU2, &serusbcfg2);
|
||||||
|
#endif
|
||||||
|
/*
|
||||||
|
* Activates the USB driver and then the USB bus pull-up on D+.
|
||||||
|
* Note, a delay is inserted in order to not have to disconnect the cable
|
||||||
|
* after a reset.
|
||||||
|
*/
|
||||||
|
usbDisconnectBus(serusbcfg1.usbp);
|
||||||
|
chThdSleep(chTimeUS2I(1500));
|
||||||
|
usbStart(serusbcfg1.usbp, &usbcfg);
|
||||||
|
usbConnectBus(serusbcfg1.usbp);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
|
@ -238,3 +238,6 @@ private:
|
|||||||
void thread_init();
|
void thread_init();
|
||||||
static void uart_thread(void *);
|
static void uart_thread(void *);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// access to usb init for stdio.cpp
|
||||||
|
void usb_initialise(void);
|
||||||
|
@ -31,6 +31,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#if HAL_USE_SERIAL_USB == TRUE
|
#if HAL_USE_SERIAL_USB == TRUE
|
||||||
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
||||||
|
#include "UARTDriver.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -85,6 +86,7 @@ int __wrap_vprintf(const char *fmt, va_list arg)
|
|||||||
#ifdef HAL_STDOUT_SERIAL
|
#ifdef HAL_STDOUT_SERIAL
|
||||||
return chvprintf((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg);
|
return chvprintf((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg);
|
||||||
#elif HAL_USE_SERIAL_USB == TRUE
|
#elif HAL_USE_SERIAL_USB == TRUE
|
||||||
|
usb_initialise();
|
||||||
return chvprintf((BaseSequentialStream*)&SDU1, fmt, arg);
|
return chvprintf((BaseSequentialStream*)&SDU1, fmt, arg);
|
||||||
#else
|
#else
|
||||||
(void)arg;
|
(void)arg;
|
||||||
|
Loading…
Reference in New Issue
Block a user