Browse Source

AP_SerialManager:correct find_baudrate() function

apm_2208
xianglunkai 3 years ago committed by Peter Barker
parent
commit
b728b8179d
  1. 2
      libraries/AP_SerialManager/AP_SerialManager.cpp

2
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -630,7 +630,7 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i @@ -630,7 +630,7 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i
if (_state == nullptr) {
return 0;
}
return state->baudrate();
return _state->baudrate();
}
// find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found

Loading…
Cancel
Save