AP_SerialManager: added find_portnum() API

used for allocating device IDs
This commit is contained in:
Andrew Tridgell 2020-12-30 12:04:27 +11:00 committed by Peter Barker
parent 5840d24ed9
commit ae4d152d51
2 changed files with 13 additions and 0 deletions

View File

@ -584,6 +584,16 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i
return map_baudrate(_state->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
{
const struct UARTState *_state = find_protocol_instance(protocol, instance);
if (_state == nullptr) {
return -1;
}
return int8_t(_state - &state[0]);
}
// get_mavlink_channel - provides the mavlink channel associated with a given protocol
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns true if a channel is found, false if not

View File

@ -174,6 +174,9 @@ public:
// returns the baudrate of that protocol on success, 0 if a serial port cannot be found
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const;
// find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found
int8_t find_portnum(enum SerialProtocol protocol, uint8_t instance) const;
// get_mavlink_channel - provides the mavlink channel associated with a given protocol (and instance)
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns true if a channel is found, false if not