mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager:correct find_baudrate() function
This commit is contained in:
parent
b365fc129d
commit
b728b8179d
|
@ -630,7 +630,7 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i
|
||||||
if (_state == nullptr) {
|
if (_state == nullptr) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
return state->baudrate();
|
return _state->baudrate();
|
||||||
}
|
}
|
||||||
|
|
||||||
// find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found
|
// find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found
|
||||||
|
|
Loading…
Reference in New Issue