mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: added have_serial() method
this checks if we have the protocol without setting the options on the uart
This commit is contained in:
parent
3dc4cdd6af
commit
d8ffd01145
|
@ -578,6 +578,12 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
|
|||
return port;
|
||||
}
|
||||
|
||||
// have_serial - return true if we have the given serial protocol configured
|
||||
bool AP_SerialManager::have_serial(enum SerialProtocol protocol, uint8_t instance) const
|
||||
{
|
||||
return find_protocol_instance(protocol, instance) != nullptr;
|
||||
}
|
||||
|
||||
// find_baudrate - searches available serial ports for the first instance that allows the given protocol
|
||||
// instance should be zero if searching for the first instance, 1 for the second, etc
|
||||
// returns baudrate on success, 0 if a serial port cannot be found
|
||||
|
|
|
@ -169,8 +169,12 @@ public:
|
|||
// find_serial - searches available serial ports that allows the given protocol
|
||||
// instance should be zero if searching for the first instance, 1 for the second, etc
|
||||
// returns uart on success, nullptr if a serial port cannot be found
|
||||
// note that the SERIALn_OPTIONS are applied if the port is found
|
||||
AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const;
|
||||
|
||||
// have_serial - return true if we have the corresponding serial protocol configured
|
||||
bool have_serial(enum SerialProtocol protocol, uint8_t instance) const;
|
||||
|
||||
// find_baudrate - searches available serial ports for the first instance that allows the given protocol
|
||||
// instance should be zero if searching for the first instance, 1 for the second, etc
|
||||
// returns the baudrate of that protocol on success, 0 if a serial port cannot be found
|
||||
|
|
Loading…
Reference in New Issue