Browse Source

AP_RCTelemetry: use have_serial when detecting

avoid find_serial() as it changes port options
c415-sdk
Andrew Tridgell 3 years ago
parent
commit
14ccee4991
  1. 4
      libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp
  2. 2
      libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp

4
libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp

@ -56,8 +56,8 @@ AP_CRSF_Telem::~AP_CRSF_Telem(void) @@ -56,8 +56,8 @@ AP_CRSF_Telem::~AP_CRSF_Telem(void)
bool AP_CRSF_Telem::init(void)
{
// sanity check that we are using a UART for RC input
if (!AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_RCIN, 0)
&& !AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) {
if (!AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 0)
&& !AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) {
return false;
}
return AP_RCTelemetry::init();

2
libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp

@ -68,7 +68,7 @@ AP_Spektrum_Telem::~AP_Spektrum_Telem(void) @@ -68,7 +68,7 @@ AP_Spektrum_Telem::~AP_Spektrum_Telem(void)
bool AP_Spektrum_Telem::init(void)
{
// sanity check that we are using a UART for RC input
if (!AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_RCIN, 0)) {
if (!AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 0)) {
return false;
}
return AP_RCTelemetry::init();

Loading…
Cancel
Save