From 061097ac31a1e68c7d8cf29274e0e1cb0740aa6a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 15 Dec 2024 15:48:36 +1100 Subject: [PATCH] AP_SerialManager: add a method to set the default baud this allows a library to change what the GCS will see in the parameter for a serial port's baud rate. --- libraries/AP_SerialManager/AP_SerialManager.cpp | 9 +++++++++ libraries/AP_SerialManager/AP_SerialManager.h | 2 ++ 2 files changed, 11 insertions(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 06afa465f4..f0f910dccd 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -676,6 +676,15 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i return _state->baudrate(); } +void AP_SerialManager::set_and_default_baud(enum SerialProtocol protocol, uint8_t instance, uint32_t _baud) +{ + const struct UARTState *_state = find_protocol_instance(protocol, instance); + if (_state == nullptr) { + return; + } + state->baud.set_and_default(_baud); +} + // find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found int8_t AP_SerialManager::find_portnum(enum SerialProtocol protocol, uint8_t instance) const { diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index be4a2be0c3..e093e75825 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -130,6 +130,8 @@ public: // accessors for AP_Periph to set baudrate and type void set_protocol_and_baud(uint8_t sernum, enum SerialProtocol protocol, uint32_t baudrate); + void set_and_default_baud(enum SerialProtocol protocol, uint8_t instance, uint32_t _baud); + static uint32_t map_baudrate(int32_t rate); // parameter var table