diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 96ac8a49bb..ed014d3303 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1294,6 +1294,7 @@ void AP_GPS::update_primary(void) } #endif // GPS_MAX_RECEIVERS > 1 +#if HAL_GCS_ENABLED void AP_GPS::handle_gps_inject(const mavlink_message_t &msg) { mavlink_gps_inject_data_t packet; @@ -1331,6 +1332,7 @@ void AP_GPS::handle_msg(const mavlink_message_t &msg) } } } +#endif #if HAL_MSP_GPS_ENABLED void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt) @@ -1496,6 +1498,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) } #endif // GPS_MAX_RECEIVERS +#if HAL_GCS_ENABLED void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) { if (inst >= GPS_MAX_RECEIVERS) { @@ -1505,6 +1508,7 @@ void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) drivers[inst]->send_mavlink_gps_rtk(chan); } } +#endif bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const { diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index 8fb6f7ed0e..6e99fbe8e7 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -34,7 +34,9 @@ public: AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message() const override { return true; } +#endif static bool _detect(struct ERB_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index ac4944a9cc..2d8d47baaf 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -45,7 +45,9 @@ public: void broadcast_configuration_failure_reason(void) const override; +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message(void) const override { return true; }; +#endif // get the velocity lag, returns true if the driver is confident in the returned value bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ; diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index 6ebeb1892d..a553588931 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -32,7 +32,9 @@ public: AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message() const override { return true; } +#endif // Methods bool read() override; diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 3b442cffc8..249edacbc4 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -197,9 +197,9 @@ bool AP_GPS_Backend::should_log() const } +#if HAL_GCS_ENABLED void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) { -#if HAL_GCS_ENABLED const uint8_t instance = state.instance; // send status switch (instance) { @@ -236,8 +236,8 @@ void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) state.rtk_iar_num_hypotheses); break; } -#endif } +#endif /* diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index ce1fac0d62..4f122b46ad 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -19,6 +19,7 @@ #pragma once #include +#include #include #include "AP_GPS.h" #include "AP_GPS_config.h" @@ -55,13 +56,15 @@ public: virtual void inject_data(const uint8_t *data, uint16_t len); +#if HAL_GCS_ENABLED //MAVLink methods virtual bool supports_mavlink_gps_rtk_message() const { return false; } virtual void send_mavlink_gps_rtk(mavlink_channel_t chan); + virtual void handle_msg(const mavlink_message_t &msg) { return ; } +#endif virtual void broadcast_configuration_failure_reason(void) const { return ; } - virtual void handle_msg(const mavlink_message_t &msg) { return ; } #if HAL_MSP_GPS_ENABLED virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; } #endif