mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
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:
parent
f26372b46e
commit
5fd0aacd6a
@ -676,6 +676,15 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i
|
||||
return _state->baudrate();
|
||||
}
|
||||
|
||||
void AP_SerialManager::set_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
|
||||
{
|
||||
|
@ -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_default_baud(enum SerialProtocol protocol, uint8_t instance, uint32_t _baud);
|
||||
|
||||
static uint32_t map_baudrate(int32_t rate);
|
||||
|
||||
// parameter var table
|
||||
|
Loading…
Reference in New Issue
Block a user