HAL_SITL: implement begin(0) on UARTs

the begin(0) is used to claim a uart for the current thread in
ChibiOS, we need to ignore it on SITL and not change baudrate
This commit is contained in:
Andrew Tridgell 2023-12-19 09:53:32 +11:00
parent 2842166b06
commit 74c2855be3
1 changed files with 6 additions and 0 deletions

View File

@ -56,6 +56,12 @@ bool UARTDriver::_console;
void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
{
if (baud == 0 && rxSpace == 0 && txSpace == 0) {
// this is a claim of the uart for the current thread, which
// is currently not implemented in SITL
return;
}
if (_portNumber >= ARRAY_SIZE(_sitlState->_serial_path)) {
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_serial_path");
}