mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_HAL_SITL: periodically warn about failure to open real UART device
This commit is contained in:
parent
67b71e2b94
commit
be2d03b02a
@ -515,6 +515,11 @@ void UARTDriver::_uart_start_connection(void)
|
||||
if (!_connected) {
|
||||
_fd = ::open(_uart_path, O_RDWR | O_CLOEXEC);
|
||||
if (_fd == -1) {
|
||||
static uint32_t last_error_print_ms;
|
||||
if (AP_HAL::millis() - last_error_print_ms > 5000) {
|
||||
::printf("Failed to open (%s): %s\n", _uart_path, strerror(errno));
|
||||
last_error_print_ms = AP_HAL::millis();
|
||||
}
|
||||
return;
|
||||
}
|
||||
// use much smaller buffer sizes on real UARTs
|
||||
|
Loading…
Reference in New Issue
Block a user