Browse Source

AP_RangeFinder: use have_serial when detecting

avoid find_serial() as it changes port options
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
366ff24941
  1. 2
      libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp

2
libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp

@ -53,7 +53,7 @@ uint32_t AP_RangeFinder_Backend_Serial::initial_baudrate(const uint8_t serial_in @@ -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…
Cancel
Save