#pragma once
#include "AP_GPS_config.h"
#if AP_GPS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS_config.h>
#include <AP_RTC/JitterCorrection.h>
#include "AP_GPS.h"
#include "AP_GPS_config.h"
#ifndef AP_GPS_DEBUG_LOGGING_ENABLED
#define AP_GPS_DEBUG_LOGGING_ENABLED 0
#endif
#ifndef AP_GPS_MB_MIN_LAG
#define AP_GPS_MB_MIN_LAG 0.05f
#endif
#ifndef AP_GPS_MB_MAX_LAG
#define AP_GPS_MB_MAX_LAG 0.25f
#endif
#if AP_GPS_DEBUG_LOGGING_ENABLED
#include <AP_HAL/utility/RingBuffer.h>
#endif
class AP_GPS_Backend
{
public:
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
virtual ~AP_GPS_Backend(void) {}
virtual bool read() = 0;
virtual AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D; }
virtual bool is_configured(void) const { return true; }
virtual void inject_data(const uint8_t *data, uint16_t len);
#if HAL_GCS_ENABLED
virtual bool supports_mavlink_gps_rtk_message() const { return false; }
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);
#endif
virtual void handle_msg(const mavlink_message_t &msg) { return ; }
#endif
virtual void broadcast_configuration_failure_reason(void) const { return ; }
#if HAL_MSP_GPS_ENABLED
virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; }
#endif
#if AP_EXTERNAL_AHRS_ENABLED
virtual void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt) { return; }
#endif
virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }
virtual bool is_healthy(void) const { return true; }
virtual bool logging_healthy(void) const { return true; }
virtual const char *name() const = 0;
void broadcast_gps_type() const;
#if HAL_LOGGING_ENABLED
virtual void Write_AP_Logger_Log_Startup_messages() const;
#endif
virtual bool prepare_for_arming(void) { return true; }
virtual bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len) { return false; }
virtual void clear_RTCMV3(void) {};
virtual bool get_error_codes(uint32_t &error_codes) const { return false; }
uint32_t get_last_itow_ms(void) const;
bool option_set(const AP_GPS::DriverOptions option) const {
return gps.option_set(option);
}
protected:
AP_HAL::UARTDriver *port;
AP_GPS &gps;
AP_GPS::GPS_State &state;
AP_GPS::Params ¶ms;
uint64_t _last_pps_time_us;
JitterCorrection jitter_correction;
uint32_t _last_itow_ms;
bool _have_itow;
void fill_3d_velocity(void);
void velocity_to_speed_course(AP_GPS::GPS_State &s);
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
void _detection_message(char *buffer, uint8_t buflen) const;
bool should_log() const;
void set_uart_timestamp(uint16_t nbytes);
void check_new_itow(uint32_t itow, uint32_t msg_length);
#if GPS_MOVING_BASELINE
bool calculate_moving_base_yaw(const float reported_heading_deg, const float reported_distance, const float reported_D);
bool calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float reported_heading_deg, const float reported_distance, const float reported_D);
#endif
AP_GPS::GPS_Type get_type() const {
return gps.get_type(state.instance);
}
virtual void set_pps_desired_freq(uint8_t freq) {}
#if AP_GPS_DEBUG_LOGGING_ENABLED
void log_data(const uint8_t *data, uint16_t length);
#endif
void set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm);
private:
uint64_t _pseudo_itow;
int32_t _pseudo_itow_delta_ms;
uint32_t _last_ms;
uint32_t _rate_ms;
uint32_t _last_rate_ms;
uint16_t _rate_counter;
#if AP_GPS_DEBUG_LOGGING_ENABLED
static struct loginfo {
int fd = -1;
ByteBuffer buf{16000};
} logging[2];
static bool log_thread_created;
static void logging_loop(void);
void logging_start(void);
#endif
};
#endif