APM:Libraries
AP_GPS_SBP.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 // Swift Navigation SBP GPS driver for ArduPilot.
18 // Code by Niels Joubert
19 //
20 // Swift Binary Protocol format: http://docs.swift-nav.com/
21 //
22 #pragma once
23 
24 #include "AP_GPS.h"
25 #include "GPS_Backend.h"
26 
27 class AP_GPS_SBP : public AP_GPS_Backend
28 {
29 public:
30  AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
31 
33 
34  bool supports_mavlink_gps_rtk_message() { return true; }
35 
36  // Methods
37  bool read();
38 
39  void inject_data(const uint8_t *data, uint16_t len) override;
40 
41  static bool _detect(struct SBP_detect_state &state, uint8_t data);
42 
43  const char *name() const override { return "SBP"; }
44 
45 private:
46 
47  // ************************************************************************
48  // Swift Navigation SBP protocol types and definitions
49  // ************************************************************************
50 
52  enum {
53  WAITING = 0,
54  GET_TYPE = 1,
56  GET_LEN = 3,
57  GET_MSG = 4,
58  GET_CRC = 5
59  } state:8;
60  uint16_t msg_type;
61  uint16_t sender_id;
62  uint16_t crc;
63  uint8_t msg_len;
64  uint8_t n_read;
65  uint8_t msg_buff[256];
66  } parser_state;
67 
68  static const uint8_t SBP_PREAMBLE = 0x55;
69 
70  //Message types supported by this driver
71  static const uint16_t SBP_STARTUP_MSGTYPE = 0xFF00;
72  static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
73  static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100;
74  static const uint16_t SBP_DOPS_MSGTYPE = 0x0206;
75  static const uint16_t SBP_POS_ECEF_MSGTYPE = 0x0200;
76  static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201;
77  static const uint16_t SBP_BASELINE_ECEF_MSGTYPE = 0x0202;
78  static const uint16_t SBP_BASELINE_NED_MSGTYPE = 0x0203;
79  static const uint16_t SBP_VEL_ECEF_MSGTYPE = 0x0204;
80  static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205;
81  static const uint16_t SBP_TRACKING_STATE_MSGTYPE = 0x0016;
82  static const uint16_t SBP_IAR_STATE_MSGTYPE = 0x0019;
83 
84  // Heartbeat
85  // struct sbp_heartbeat_t {
86  // uint32_t flags; //< Status flags (reserved)
87  // }; // 4 bytes
89  bool sys_error : 1;
90  bool io_error : 1;
91  bool nap_error : 1;
92  uint8_t res : 5;
93  uint8_t protocol_minor : 8;
94  uint8_t protocol_major : 8;
95  uint8_t res2 : 7;
96  bool ext_antenna : 1;
97  }; // 4 bytes
98 
99  // GPS Time
101  uint16_t wn; //< GPS week number (unit: weeks)
102  uint32_t tow; //< GPS Time of Week rounded to the nearest ms (unit: ms)
103  int32_t ns; //< Nanosecond remainder of rounded tow (unit: ns)
104  uint8_t flags; //< Status flags (reserved)
105  }; // 11 bytes
106 
107  // Dilution of Precision
109  uint32_t tow; //< GPS Time of Week (unit: ms)
110  uint16_t gdop; //< Geometric Dilution of Precision (unit: 0.01)
111  uint16_t pdop; //< Position Dilution of Precision (unit: 0.01)
112  uint16_t tdop; //< Time Dilution of Precision (unit: 0.01)
113  uint16_t hdop; //< Horizontal Dilution of Precision (unit: 0.01)
114  uint16_t vdop; //< Vertical Dilution of Precision (unit: 0.01)
115  }; // 14 bytes
116 
117  // Geodetic position solution.
119  uint32_t tow; //< GPS Time of Week (unit: ms)
120  double lat; //< Latitude (unit: degrees)
121  double lon; //< Longitude (unit: degrees)
122  double height; //< Height (unit: meters)
123  uint16_t h_accuracy; //< Horizontal position accuracy estimate (unit: mm)
124  uint16_t v_accuracy; //< Vertical position accuracy estimate (unit: mm)
125  uint8_t n_sats; //< Number of satellites used in solution
126  uint8_t flags; //< Status flags
127  }; // 34 bytes
128 
129  // Velocity in NED Velocity in local North East Down (NED) coordinates.
131  uint32_t tow; //< GPS Time of Week (unit: ms)
132  int32_t n; //< Velocity North coordinate (unit: mm/s)
133  int32_t e; //< Velocity East coordinate (unit: mm/s)
134  int32_t d; //< Velocity Down coordinate (unit: mm/s)
135  uint16_t h_accuracy; //< Horizontal velocity accuracy estimate (unit: mm/s)
136  uint16_t v_accuracy; //< Vertical velocity accuracy estimate (unit: mm/s)
137  uint8_t n_sats; //< Number of satellites used in solution
138  uint8_t flags; //< Status flags (reserved)
139  }; // 22 bytes
140 
141  // Activity and Signal-to-Noise data of a tracking channel on the GPS.
143  uint8_t state; //< 0 if disabled, 1 if running
144  uint8_t prn; //< PRN identifier of tracked satellite
145  float cn0; //< carrier to noise power ratio.
146  };
147 
148  // Integer Ambiguity Resolution state - how is the RTK resolution doing?
150  uint32_t num_hypotheses;
151  };
152 
153  void _sbp_process();
154  void _sbp_process_message();
155  bool _attempt_state_update();
156 
157  // ************************************************************************
158  // Internal Received Messages State
159  // ************************************************************************
162 
169 
172 
173  // ************************************************************************
174  // Monitoring and Performance Counting
175  // ************************************************************************
176 
178 
179  // ************************************************************************
180  // Logging to DataFlash
181  // ************************************************************************
182 
184  void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
185 
186 
187 };
Definition: AP_GPS.h:48
static const uint16_t SBP_VEL_NED_MSGTYPE
Definition: AP_GPS_SBP.h:80
AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBP.cpp:47
static const uint16_t SBP_POS_ECEF_MSGTYPE
Definition: AP_GPS_SBP.h:75
struct AP_GPS_SBP::sbp_parser_state_t parser_state
const char * name() const override
Definition: AP_GPS_SBP.h:43
uint32_t last_full_update_cpu_ms
Definition: AP_GPS_SBP.h:171
struct sbp_pos_llh_t last_pos_llh_rtk
Definition: AP_GPS_SBP.h:166
static const uint8_t SBP_PREAMBLE
Definition: AP_GPS_SBP.h:68
void logging_log_full_update()
Definition: AP_GPS_SBP.cpp:388
bool supports_mavlink_gps_rtk_message()
Definition: AP_GPS_SBP.h:34
bool _attempt_state_update()
Definition: AP_GPS_SBP.cpp:228
static const uint16_t SBP_IAR_STATE_MSGTYPE
Definition: AP_GPS_SBP.h:82
void _sbp_process_message()
Definition: AP_GPS_SBP.cpp:177
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
struct sbp_vel_ned_t last_vel_ned
Definition: AP_GPS_SBP.h:167
struct sbp_pos_llh_t last_pos_llh_spp
Definition: AP_GPS_SBP.h:165
static const uint16_t SBP_HEARTBEAT_MSGTYPE
Definition: AP_GPS_SBP.h:72
static const uint16_t SBP_TRACKING_STATE_MSGTYPE
Definition: AP_GPS_SBP.h:81
static const uint16_t SBP_GPS_TIME_MSGTYPE
Definition: AP_GPS_SBP.h:73
uint32_t crc_error_counter
Definition: AP_GPS_SBP.h:177
static const uint16_t SBP_POS_LLH_MSGTYPE
Definition: AP_GPS_SBP.h:76
static const uint16_t SBP_STARTUP_MSGTYPE
Definition: AP_GPS_SBP.h:71
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
uint32_t last_iar_num_hypotheses
Definition: AP_GPS_SBP.h:168
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff)
Definition: AP_GPS_SBP.cpp:407
static const uint16_t SBP_BASELINE_NED_MSGTYPE
Definition: AP_GPS_SBP.h:78
void inject_data(const uint8_t *data, uint16_t len) override
Definition: AP_GPS_SBP.cpp:80
enum AP_GPS_SBP::sbp_parser_state_t::@33 state
void _sbp_process()
Definition: AP_GPS_SBP.cpp:95
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_SBP.h:32
#define PACKED
Definition: AP_Common.h:28
static bool _detect(struct SBP_detect_state &state, uint8_t data)
Definition: AP_GPS_SBP.cpp:311
struct sbp_dops_t last_dops
Definition: AP_GPS_SBP.h:164
struct sbp_gps_time_t last_gps_time
Definition: AP_GPS_SBP.h:163
static const uint16_t SBP_DOPS_MSGTYPE
Definition: AP_GPS_SBP.h:74
static const uint16_t SBP_BASELINE_ECEF_MSGTYPE
Definition: AP_GPS_SBP.h:77
bool read()
Definition: AP_GPS_SBP.cpp:65
uint32_t last_injected_data_ms
Definition: AP_GPS_SBP.h:161
uint32_t last_heatbeat_received_ms
Definition: AP_GPS_SBP.h:160
static const uint16_t SBP_VEL_ECEF_MSGTYPE
Definition: AP_GPS_SBP.h:79
uint32_t last_full_update_tow
Definition: AP_GPS_SBP.h:170