mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: display uart even when not initialised
don't rely on thread allocation for uart info display
This commit is contained in:
parent
c34d8e80e9
commit
3128d71aac
@ -1673,8 +1673,12 @@ uint8_t UARTDriver::get_options(void) const
|
||||
void UARTDriver::uart_info(ExpandingString &str)
|
||||
{
|
||||
uint32_t now_ms = AP_HAL::millis();
|
||||
str.printf("%-5s TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u\n",
|
||||
uart_thread_name,
|
||||
if (sdef.is_usb) {
|
||||
str.printf("OTG%u ", unsigned(sdef.instance));
|
||||
} else {
|
||||
str.printf("UART%u ", unsigned(sdef.instance));
|
||||
}
|
||||
str.printf("TX%c=%8u RX%c=%8u TXBD=%6u RXBD=%6u\n",
|
||||
tx_dma_enabled ? '*' : ' ',
|
||||
unsigned(_tx_stats_bytes),
|
||||
rx_dma_enabled ? '*' : ' ',
|
||||
|
Loading…
Reference in New Issue
Block a user