AP_GPS: avoid use of mavlink constructs when GCS not compiled in

This commit is contained in:
Peter Barker 2023-08-04 08:22:39 +10:00 committed by Andrew Tridgell
parent bf005731a9
commit 6ee9f01ffb
6 changed files with 16 additions and 3 deletions

View File

@ -1294,6 +1294,7 @@ void AP_GPS::update_primary(void)
} }
#endif // GPS_MAX_RECEIVERS > 1 #endif // GPS_MAX_RECEIVERS > 1
#if HAL_GCS_ENABLED
void AP_GPS::handle_gps_inject(const mavlink_message_t &msg) void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
{ {
mavlink_gps_inject_data_t packet; 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 #if HAL_MSP_GPS_ENABLED
void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt) 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 #endif // GPS_MAX_RECEIVERS
#if HAL_GCS_ENABLED
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
{ {
if (inst >= GPS_MAX_RECEIVERS) { 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); drivers[inst]->send_mavlink_gps_rtk(chan);
} }
} }
#endif
bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const
{ {

View File

@ -34,7 +34,9 @@ public:
AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } 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; } bool supports_mavlink_gps_rtk_message() const override { return true; }
#endif
static bool _detect(struct ERB_detect_state &state, uint8_t data); static bool _detect(struct ERB_detect_state &state, uint8_t data);

View File

@ -45,7 +45,9 @@ public:
void broadcast_configuration_failure_reason(void) const override; void broadcast_configuration_failure_reason(void) const override;
#if HAL_GCS_ENABLED
bool supports_mavlink_gps_rtk_message(void) const override { return true; }; 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 // 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; } ; bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ;

View File

@ -32,7 +32,9 @@ public:
AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } 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; } bool supports_mavlink_gps_rtk_message() const override { return true; }
#endif
// Methods // Methods
bool read() override; bool read() override;

View File

@ -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) void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
{ {
#if HAL_GCS_ENABLED
const uint8_t instance = state.instance; const uint8_t instance = state.instance;
// send status // send status
switch (instance) { switch (instance) {
@ -236,8 +236,8 @@ void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
state.rtk_iar_num_hypotheses); state.rtk_iar_num_hypotheses);
break; break;
} }
#endif
} }
#endif
/* /*

View File

@ -19,6 +19,7 @@
#pragma once #pragma once
#include <GCS_MAVLink/GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS_config.h>
#include <AP_RTC/JitterCorrection.h> #include <AP_RTC/JitterCorrection.h>
#include "AP_GPS.h" #include "AP_GPS.h"
#include "AP_GPS_config.h" #include "AP_GPS_config.h"
@ -55,13 +56,15 @@ public:
virtual void inject_data(const uint8_t *data, uint16_t len); virtual void inject_data(const uint8_t *data, uint16_t len);
#if HAL_GCS_ENABLED
//MAVLink methods //MAVLink methods
virtual bool supports_mavlink_gps_rtk_message() const { return false; } virtual bool supports_mavlink_gps_rtk_message() const { return false; }
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan); 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 broadcast_configuration_failure_reason(void) const { return ; }
virtual void handle_msg(const mavlink_message_t &msg) { return ; }
#if HAL_MSP_GPS_ENABLED #if HAL_MSP_GPS_ENABLED
virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; } virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; }
#endif #endif