36 virtual bool read() = 0;
44 virtual void inject_data(
const uint8_t *data, uint16_t len);
52 virtual void handle_msg(
const mavlink_message_t *msg) { return ; }
56 virtual bool get_lag(
float &lag)
const { lag = 0.2f;
return true; }
61 virtual const char *
name()
const = 0;
86 void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
virtual bool supports_mavlink_gps_rtk_message()
virtual AP_GPS::GPS_Status highest_supported_status(void)
virtual bool get_lag(float &lag) const
virtual void broadcast_configuration_failure_reason(void) const
static uint8_t buffer[SRXL_FRAMELEN_MAX]
virtual void inject_data(const uint8_t *data, uint16_t len)
virtual ~AP_GPS_Backend(void)
virtual void handle_gnss_msg(const AP_GPS::GPS_State &msg)
virtual bool prepare_for_arming(void)
int32_t swap_int32(int32_t v) const
AP_GPS & gps
access to frontend (for parameters)
GPS_Status
GPS status codes.
virtual bool is_healthy(void) const
virtual const char * name() const =0
virtual void send_mavlink_gps_rtk(mavlink_channel_t chan)
void broadcast_gps_type() const
virtual void handle_msg(const mavlink_message_t *msg)
virtual bool is_configured(void)
AP_GPS::GPS_State & state
public state for this instance
bool should_df_log() const
void _detection_message(char *buffer, uint8_t buflen) const
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
void fill_3d_velocity(void)
int16_t swap_int16(int16_t v) const
AP_HAL::AnalogSource * chan
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
AP_HAL::UARTDriver * port
UART we are attached to.
virtual void Write_DataFlash_Log_Startup_messages() const
Receiving valid messages and 3D lock.