APM:Libraries
GPS_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  GPS driver backend class
18  */
19 #pragma once
20 
22 #include "AP_GPS.h"
23 
25 {
26 public:
28 
29  // we declare a virtual destructor so that GPS drivers can
30  // override with a custom destructor if need be.
31  virtual ~AP_GPS_Backend(void) {}
32 
33  // The read() method is the only one needed in each driver. It
34  // should return true when the backend has successfully received a
35  // valid packet from the GPS.
36  virtual bool read() = 0;
37 
38  // Highest status supported by this GPS.
39  // Allows external system to identify type of receiver connected.
41 
42  virtual bool is_configured(void) { return true; }
43 
44  virtual void inject_data(const uint8_t *data, uint16_t len);
45 
46  //MAVLink methods
47  virtual bool supports_mavlink_gps_rtk_message() { return false; }
48  virtual void send_mavlink_gps_rtk(mavlink_channel_t chan);
49 
50  virtual void broadcast_configuration_failure_reason(void) const { return ; }
51 
52  virtual void handle_msg(const mavlink_message_t *msg) { return ; }
53  virtual void handle_gnss_msg(const AP_GPS::GPS_State &msg) { return ; }
54 
55  // driver specific lag, returns true if the driver is confident in the provided lag
56  virtual bool get_lag(float &lag) const { lag = 0.2f; return true; }
57 
58  // driver specific health, returns true if the driver is healthy
59  virtual bool is_healthy(void) const { return true; }
60 
61  virtual const char *name() const = 0;
62 
63  void broadcast_gps_type() const;
64  virtual void Write_DataFlash_Log_Startup_messages() const;
65 
66  virtual bool prepare_for_arming(void) { return true; }
67 
68 protected:
72 
73  // common utility functions
74  int32_t swap_int32(int32_t v) const;
75  int16_t swap_int16(int16_t v) const;
76 
77  /*
78  fill in 3D velocity from 2D components
79  */
80  void fill_3d_velocity(void);
81 
82  /*
83  fill in time_week_ms and time_week from BCD date and time components
84  assumes MTK19 millisecond form of bcd_time
85  */
86  void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
87 
88  void _detection_message(char *buffer, uint8_t buflen) const;
89 
90  bool should_df_log() const;
91 };
Definition: AP_GPS.h:48
virtual bool supports_mavlink_gps_rtk_message()
Definition: GPS_Backend.h:47
virtual AP_GPS::GPS_Status highest_supported_status(void)
Definition: GPS_Backend.h:40
virtual bool get_lag(float &lag) const
Definition: GPS_Backend.h:56
virtual void broadcast_configuration_failure_reason(void) const
Definition: GPS_Backend.h:50
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
virtual void inject_data(const uint8_t *data, uint16_t len)
virtual ~AP_GPS_Backend(void)
Definition: GPS_Backend.h:31
virtual void handle_gnss_msg(const AP_GPS::GPS_State &msg)
Definition: GPS_Backend.h:53
virtual bool prepare_for_arming(void)
Definition: GPS_Backend.h:66
int32_t swap_int32(int32_t v) const
Definition: GPS_Backend.cpp:41
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
virtual bool is_healthy(void) const
Definition: GPS_Backend.h:59
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)
Definition: GPS_Backend.h:52
virtual bool is_configured(void)
Definition: GPS_Backend.h:42
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
float v
Definition: Printf.cpp:15
bool should_df_log() const
void _detection_message(char *buffer, uint8_t buflen) const
static uint8_t buflen
Definition: srxl.cpp:57
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: GPS_Backend.cpp:31
void fill_3d_velocity(void)
int16_t swap_int16(int16_t v) const
Definition: GPS_Backend.cpp:57
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
Definition: GPS_Backend.cpp:76
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
virtual void Write_DataFlash_Log_Startup_messages() const
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
virtual bool read()=0