APM:Libraries
AP_GPS_SBP2.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 
28 {
29 public:
31 
33 
34  // Methods
35  bool read() override;
36 
37  void inject_data(const uint8_t *data, uint16_t len) override;
38 
39  static bool _detect(struct SBP2_detect_state &state, uint8_t data);
40 
41  const char *name() const override { return "SBP2"; }
42 
43 private:
44 
45  // ************************************************************************
46  // Swift Navigation SBP protocol types and definitions
47  // ************************************************************************
48 
50  enum {
51  WAITING = 0,
52  GET_TYPE = 1,
54  GET_LEN = 3,
55  GET_MSG = 4,
56  GET_CRC = 5
57  } state:8;
58  uint16_t msg_type;
59  uint16_t sender_id;
60  uint16_t crc;
61  uint8_t msg_len;
62  uint8_t n_read;
63  uint8_t msg_buff[256];
64  } parser_state;
65 
66  static const uint8_t SBP_PREAMBLE = 0x55;
67 
68  // Message types supported by this driver
69  static const uint16_t SBP_STARTUP_MSGTYPE = 0xFF00;
70  static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
71  static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0102;
72  static const uint16_t SBP_DOPS_MSGTYPE = 0x0208;
73  static const uint16_t SBP_POS_ECEF_MSGTYPE = 0x0209;
74  static const uint16_t SBP_POS_LLH_MSGTYPE = 0x020A;
75  static const uint16_t SBP_BASELINE_ECEF_MSGTYPE = 0x020B;
76  static const uint16_t SBP_BASELINE_NED_MSGTYPE = 0x020C;
77  static const uint16_t SBP_VEL_ECEF_MSGTYPE = 0x020D;
78  static const uint16_t SBP_VEL_NED_MSGTYPE = 0x020E;
79  static const uint16_t SBP_TRACKING_STATE_MSGTYPE = 0x0013;
80  static const uint16_t SBP_IAR_STATE_MSGTYPE = 0x0019;
81  static const uint16_t SBP_EXT_EVENT_MSGTYPE = 0x0101;
82 
83  // Heartbeat
85  bool sys_error : 1;
86  bool io_error : 1;
87  bool nap_error : 1;
88  uint8_t res : 5;
89  uint8_t protocol_minor : 8;
90  uint8_t protocol_major : 8;
91  uint8_t res2 : 7;
92  bool ext_antenna : 1;
93  }; // 4 bytes
94 
95  // GPS Time
97  uint16_t wn; //< GPS week number (unit: weeks)
98  uint32_t tow; //< GPS Time of Week rounded to the nearest ms (unit: ms)
99  int32_t ns; //< Nanosecond remainder of rounded tow (unit: ns)
100  struct PACKED flags {
101  uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX
102  uint8_t res:5; //< Reserved
103  } flags;
104  }; // 11 bytes
105 
106  // Dilution of Precision
108  uint32_t tow; //< GPS Time of Week (unit: ms)
109  uint16_t gdop; //< Geometric Dilution of Precision (unit: 0.01)
110  uint16_t pdop; //< Position Dilution of Precision (unit: 0.01)
111  uint16_t tdop; //< Time Dilution of Precision (unit: 0.01)
112  uint16_t hdop; //< Horizontal Dilution of Precision (unit: 0.01)
113  uint16_t vdop; //< Vertical Dilution of Precision (unit: 0.01)
114  struct PACKED flags {
115  uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX
116  uint8_t res:4; //< Reserved
117  bool raim_repair:1; //< Solution from RAIM?
118  } flags;
119  }; // 15 bytes
120 
121  // Geodetic position solution.
123  uint32_t tow; //< GPS Time of Week (unit: ms)
124  double lat; //< Latitude (unit: degrees)
125  double lon; //< Longitude (unit: degrees)
126  double height; //< Height (unit: meters)
127  uint16_t h_accuracy; //< Horizontal position accuracy estimate (unit: mm)
128  uint16_t v_accuracy; //< Vertical position accuracy estimate (unit: mm)
129  uint8_t n_sats; //< Number of satellites used in solution
130  struct PACKED flags {
131  uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX
132  uint8_t res:4; //< Reserved
133  bool raim_repair:1; //< Solution from RAIM?
134  } flags;
135  }; // 34 bytes
136 
137  // Velocity in NED Velocity in local North East Down (NED) coordinates.
139  uint32_t tow; //< GPS Time of Week (unit: ms)
140  int32_t n; //< Velocity North coordinate (unit: mm/s)
141  int32_t e; //< Velocity East coordinate (unit: mm/s)
142  int32_t d; //< Velocity Down coordinate (unit: mm/s)
143  uint16_t h_accuracy; //< Horizontal velocity accuracy estimate (unit: mm/s)
144  uint16_t v_accuracy; //< Vertical velocity accuracy estimate (unit: mm/s)
145  uint8_t n_sats; //< Number of satellites used in solution
146  struct PACKED flags {
147  uint8_t fix_mode:3; //< Fix mode (0: invalid, 1: SPP, 2: DGNSS, 3: Float RTX, 4: Fixed RTX
148  uint8_t res:5; //< Reserved
149  } flags;
150  }; // 22 bytes
151 
152  // Messages reporting accurately-timestamped external events, e.g. camera shutter time.
154  uint16_t wn; //< GPS week number (unit: weeks)
155  uint32_t tow; //< GPS Time of Week (unit: ms)
156  int32_t ns_residual; //< Nanosecond residual of millisecond-rounded TOW (ranges from -500000 to 500000)
157  struct PACKED flags {
158  uint8_t level:1; //< New level of pin values (0: Low (falling edge), 1: High (rising edge))
159  uint8_t quality:1; //< Time quality values (0: Unknown - don't have nav solution, 1: Good (< 1 microsecond))
160  uint8_t res:6; //< Reserved
161  } flags;
162  }; // 12 bytes
163 
164  void _sbp_process();
165  void _sbp_process_message();
166  bool _attempt_state_update();
167 
168  // ************************************************************************
169  // Internal Received Messages State
170  // ************************************************************************
173 
180 
183 
184  // ************************************************************************
185  // Monitoring and Performance Counting
186  // ************************************************************************
187 
189 
190  // ************************************************************************
191  // Logging to DataFlash
192  // ************************************************************************
193 
195  void logging_ext_event();
196  void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff);
197 
198  int32_t distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod);
199 
200 };
201 
Definition: AP_GPS.h:48
static const uint16_t SBP_DOPS_MSGTYPE
Definition: AP_GPS_SBP2.h:72
void logging_log_full_update()
static const uint8_t SBP_PREAMBLE
Definition: AP_GPS_SBP2.h:66
AP_GPS::GPS_Status highest_supported_status(void) override
Definition: AP_GPS_SBP2.h:32
static const uint16_t SBP_TRACKING_STATE_MSGTYPE
Definition: AP_GPS_SBP2.h:79
bool _attempt_state_update()
static const uint16_t SBP_POS_ECEF_MSGTYPE
Definition: AP_GPS_SBP2.h:73
struct sbp_vel_ned_t last_vel_ned
Definition: AP_GPS_SBP2.h:178
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff)
struct sbp_heartbeat_t last_heartbeat
Definition: AP_GPS_SBP2.h:174
enum AP_GPS_SBP2::sbp_parser_state_t::@34 state
struct sbp_pos_llh_t last_pos_llh
Definition: AP_GPS_SBP2.h:177
bool read() override
Definition: AP_GPS_SBP2.cpp:72
struct sbp_dops_t last_dops
Definition: AP_GPS_SBP2.h:176
uint32_t crc_error_counter
Definition: AP_GPS_SBP2.h:188
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
uint32_t last_heartbeat_received_ms
Definition: AP_GPS_SBP2.h:171
uint32_t last_injected_data_ms
Definition: AP_GPS_SBP2.h:172
static const uint16_t SBP_VEL_ECEF_MSGTYPE
Definition: AP_GPS_SBP2.h:77
void _sbp_process()
Definition: AP_GPS_SBP2.cpp:97
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
static const uint16_t SBP_VEL_NED_MSGTYPE
Definition: AP_GPS_SBP2.h:78
static const uint16_t SBP_BASELINE_NED_MSGTYPE
Definition: AP_GPS_SBP2.h:76
AP_GPS_SBP2(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBP2.cpp:61
static const uint16_t SBP_POS_LLH_MSGTYPE
Definition: AP_GPS_SBP2.h:74
static const uint16_t SBP_EXT_EVENT_MSGTYPE
Definition: AP_GPS_SBP2.h:81
static bool _detect(struct SBP2_detect_state &state, uint8_t data)
struct sbp_ext_event_t last_event
Definition: AP_GPS_SBP2.h:179
uint16_t last_full_update_wn
Definition: AP_GPS_SBP2.h:182
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
uint32_t last_full_update_tow
Definition: AP_GPS_SBP2.h:181
static const uint16_t SBP_STARTUP_MSGTYPE
Definition: AP_GPS_SBP2.h:69
static const uint16_t SBP_HEARTBEAT_MSGTYPE
Definition: AP_GPS_SBP2.h:70
static const uint16_t SBP_IAR_STATE_MSGTYPE
Definition: AP_GPS_SBP2.h:80
void logging_ext_event()
#define PACKED
Definition: AP_Common.h:28
void inject_data(const uint8_t *data, uint16_t len) override
Definition: AP_GPS_SBP2.cpp:84
const char * name() const override
Definition: AP_GPS_SBP2.h:41
static const uint16_t SBP_GPS_TIME_MSGTYPE
Definition: AP_GPS_SBP2.h:71
struct AP_GPS_SBP2::sbp_parser_state_t parser_state
int32_t distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod)
static const uint16_t SBP_BASELINE_ECEF_MSGTYPE
Definition: AP_GPS_SBP2.h:75
void _sbp_process_message()
struct sbp_gps_time_t last_gps_time
Definition: AP_GPS_SBP2.h:175