SerialManager: use instance in find_baudrate

This commit is contained in:
Mike Clement 2015-04-06 14:47:11 -07:00
parent 9b3656e77c
commit 89a50b99bb
2 changed files with 10 additions and 3 deletions

View File

@ -187,14 +187,20 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
}
// 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
uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol) const
uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
{
uint8_t found_instance = 0;
// search for matching protocol
for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
if ((enum SerialProtocol)state[i].protocol.get() == protocol) {
if (found_instance == instance) {
return map_baudrate(state[i].baud);
}
found_instance++;
}
}
// if we got this far we did not find the uart

View File

@ -93,8 +93,9 @@ public:
AP_HAL::UARTDriver *find_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
uint32_t find_baudrate(enum SerialProtocol protocol) const;
uint32_t find_baudrate(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