ardupilot icon indicating copy to clipboard operation
ardupilot copied to clipboard

AP_HAL_Linux: Support "non-standard" baudrates on UART

Open nbertram opened this issue 2 years ago • 0 comments

The current glibc-based UART code using termios.h and cfsetspeed() isn't (usually) capable of setting baudrates outside the standard set. I discovered this on a Beaglebone Blue trying to use a ELRS (CRSF) RX which wants 416666 baud. The existing call to cfsetspeed() was failing silently in this case (I observed with stty that the port was remaining at 115200 throughout the RC protocol search).

Using the Linux-specific ioctl to set custom bauds using CBAUDEX fixed the issue. I also added some rudimentary error logging which wasn't present originally.

I note that the SITL UART_utils.cpp already uses this ioctl, though is using a different option to set a custom baud (tc.c_cflag |= BOTHER). I'm not sure if it's worth attempting a consolidation of Linux serial handling code across these contexts, open to suggestions.

nbertram avatar Sep 22 '22 09:09 nbertram