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.
This commit is contained in:
Peter Barker 2024-12-15 15:48:36 +11:00 committed by Peter Barker
parent 8717921c56
commit 061097ac31
2 changed files with 11 additions and 0 deletions

View File

@ -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
{

View File

@ -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