mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_SerialManager: added find_portnum() API
used for allocating device IDs
This commit is contained in:
parent
5840d24ed9
commit
ae4d152d51
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user