Browse Source

AP_ADSB: use have_serial when detecting

avoid find_serial() as it changes port options
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
0da0f6dd37
  1. 2
      libraries/AP_ADSB/AP_ADSB_Sagetech.cpp
  2. 2
      libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp

2
libraries/AP_ADSB/AP_ADSB_Sagetech.cpp

@ -45,7 +45,7 @@ @@ -45,7 +45,7 @@
// detect if any port is configured as Sagetech
bool AP_ADSB_Sagetech::detect()
{
return (AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0) != nullptr);
return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0);
}
// Init, called once after class is constructed

2
libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp

@ -45,7 +45,7 @@ extern const AP_HAL::HAL &hal; @@ -45,7 +45,7 @@ extern const AP_HAL::HAL &hal;
// detect if any port is configured as uAvionix_UCP
bool AP_ADSB_uAvionix_UCP::detect()
{
return (AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0) != nullptr);
return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0);
}

Loading…
Cancel
Save