mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: use have_serial when detecting
avoid find_serial() as it changes port options
This commit is contained in:
parent
f516977491
commit
0a018c323c
|
@ -53,7 +53,7 @@ uint32_t AP_RangeFinder_Backend_Serial::initial_baudrate(const uint8_t serial_in
|
|||
*/
|
||||
bool AP_RangeFinder_Backend_Serial::detect(uint8_t serial_instance)
|
||||
{
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
}
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue