mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
GCS_MAVLink: allow FRSky to be compiled out
This commit is contained in:
parent
64193542ed
commit
850d47752f
@ -18,6 +18,7 @@
|
|||||||
#include <AP_LTM_Telem/AP_LTM_Telem.h>
|
#include <AP_LTM_Telem/AP_LTM_Telem.h>
|
||||||
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
#include <AP_Devo_Telem/AP_Devo_Telem.h>
|
||||||
#include <AP_Filesystem/AP_Filesystem_config.h>
|
#include <AP_Filesystem/AP_Filesystem_config.h>
|
||||||
|
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
@ -1098,8 +1099,10 @@ public:
|
|||||||
|
|
||||||
bool out_of_time() const;
|
bool out_of_time() const;
|
||||||
|
|
||||||
|
#if AP_FRSKY_TELEM_ENABLED
|
||||||
// frsky backend
|
// frsky backend
|
||||||
class AP_Frsky_Telem *frsky;
|
class AP_Frsky_Telem *frsky;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_LTM_TELEM_ENABLED
|
#if AP_LTM_TELEM_ENABLED
|
||||||
// LTM backend
|
// LTM backend
|
||||||
|
@ -2060,10 +2060,12 @@ void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, u
|
|||||||
logger->Write_Message(first_piece_of_text);
|
logger->Write_Message(first_piece_of_text);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_FRSKY_TELEM_ENABLED
|
||||||
frsky = AP::frsky_telem();
|
frsky = AP::frsky_telem();
|
||||||
if (frsky != nullptr) {
|
if (frsky != nullptr) {
|
||||||
frsky->queue_message(severity, first_piece_of_text);
|
frsky->queue_message(severity, first_piece_of_text);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
#if HAL_SPEKTRUM_TELEM_ENABLED
|
#if HAL_SPEKTRUM_TELEM_ENABLED
|
||||||
AP_Spektrum_Telem* spektrum = AP::spektrum_telem();
|
AP_Spektrum_Telem* spektrum = AP::spektrum_telem();
|
||||||
if (spektrum != nullptr) {
|
if (spektrum != nullptr) {
|
||||||
@ -2316,6 +2318,7 @@ void GCS::setup_uarts()
|
|||||||
create_gcs_mavlink_backend(chan_parameters[i], *uart);
|
create_gcs_mavlink_backend(chan_parameters[i], *uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_FRSKY_TELEM_ENABLED
|
||||||
if (frsky == nullptr) {
|
if (frsky == nullptr) {
|
||||||
frsky = new AP_Frsky_Telem();
|
frsky = new AP_Frsky_Telem();
|
||||||
if (frsky == nullptr || !frsky->init()) {
|
if (frsky == nullptr || !frsky->init()) {
|
||||||
@ -2323,6 +2326,8 @@ void GCS::setup_uarts()
|
|||||||
frsky = nullptr;
|
frsky = nullptr;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_LTM_TELEM_ENABLED
|
#if AP_LTM_TELEM_ENABLED
|
||||||
ltm_telemetry.init();
|
ltm_telemetry.init();
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user