diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index a9037ad8f8..08bc5a06fa 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -103,7 +103,7 @@ void AP_RCProtocol_FPort::decode_control(const FPort_Frame &frame) */ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame) { -#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) +#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) && AP_FRSKY_SPORT_TELEM_ENABLED switch (frame.downlink.prim) { case FPORT_PRIM_DATA: // we've seen at least one 0x10 frame diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h index e1287a212a..a060c3b6a6 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h @@ -53,10 +53,12 @@ private: const bool inverted; +#if AP_FRSKY_SPORT_TELEM_ENABLED struct { bool available = false; AP_Frsky_SPort::sport_packet_t packet; } telem_data; +#endif // AP_FRSKY_SPORT_TELEM_ENABLED // receiver sends 0x10 when ready to receive telemetry frames (R-XSR) bool rx_driven_frame_rate = false; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index 26a225ad21..5619c5373c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -20,7 +20,7 @@ #endif #ifndef AP_RCPROTOCOL_FPORT_ENABLED -#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED +#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_RCPROTOCOL_FPORT2_ENABLED #define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED