From 10aa028d150b1256931999c471e9f61de9a7dbf5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Feb 2024 14:46:34 +1100 Subject: [PATCH] AP_SerialManager: default GPS baud to 230400 this is the most common baudrate --- libraries/AP_SerialManager/AP_SerialManager_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index a09a2995a0..803fdd7219 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -93,7 +93,7 @@ // GPS default baud rates and buffer sizes // we need a 256 byte buffer for some GPS types (eg. UBLOX) -#define AP_SERIALMANAGER_GPS_BAUD 38400 +#define AP_SERIALMANAGER_GPS_BAUD 230400 #define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256 #define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16