mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: use have_serial when detecting
avoid find_serial() as it changes port options
This commit is contained in:
parent
0a018c323c
commit
14ccee4991
|
@ -56,8 +56,8 @@ AP_CRSF_Telem::~AP_CRSF_Telem(void)
|
||||||
bool AP_CRSF_Telem::init(void)
|
bool AP_CRSF_Telem::init(void)
|
||||||
{
|
{
|
||||||
// sanity check that we are using a UART for RC input
|
// 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)
|
||||||
&& !AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) {
|
&& !AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return AP_RCTelemetry::init();
|
return AP_RCTelemetry::init();
|
||||||
|
|
|
@ -68,7 +68,7 @@ AP_Spektrum_Telem::~AP_Spektrum_Telem(void)
|
||||||
bool AP_Spektrum_Telem::init(void)
|
bool AP_Spektrum_Telem::init(void)
|
||||||
{
|
{
|
||||||
// sanity check that we are using a UART for RC input
|
// 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 false;
|
||||||
}
|
}
|
||||||
return AP_RCTelemetry::init();
|
return AP_RCTelemetry::init();
|
||||||
|
|
Loading…
Reference in New Issue