APM:Libraries
AP_GPS_SBF.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 // Septentrio GPS driver for ArduPilot.
18 // Code by Michael Oborne
19 //
20 #pragma once
21 
22 #include "AP_GPS.h"
23 #include "GPS_Backend.h"
24 
25 #define SBF_SETUP_MSG "\nsso, Stream1, COM1, PVTGeodetic+DOP+ExtEventPVTGeodetic, msec100\n"
26 #define SBF_DISK_ACTIVITY (1 << 7)
27 #define SBF_DISK_FULL (1 << 8)
28 #define SBF_DISK_MOUNTED (1 << 9)
29 
30 class AP_GPS_SBF : public AP_GPS_Backend
31 {
32 public:
33  AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
34 
36 
37  // Methods
38  bool read();
39 
40  const char *name() const override { return "SBF"; }
41 
42  bool is_configured (void) override;
43 
44  void broadcast_configuration_failure_reason(void) const override;
45 
46  // get the velocity lag, returns true if the driver is confident in the returned value
47  bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ;
48 
49  bool is_healthy(void) const override;
50 
51  bool prepare_for_arming(void) override;
52 
53 
54 private:
55 
56  bool parse(uint8_t temp);
57  bool process_message();
58 
59  static const uint8_t SBF_PREAMBLE1 = '$';
60  static const uint8_t SBF_PREAMBLE2 = '@';
61 
62  uint8_t _init_blob_index = 0;
63  uint32_t _init_blob_time = 0;
64  const char* _initialisation_blob[5] = {
65  "sso, Stream1, COM1, PVTGeodetic+DOP+ExtEventPVTGeodetic+ReceiverStatus+VelCovGeodetic, msec100\n",
66  "srd, Moderate, UAV\n",
67  "sem, PVT, 5\n",
68  "spm, Rover, all\n",
69  "sso, Stream2, Dsk1, postprocess+event+comment, msec100\n"};
71 
72  const char* _port_enable = "\nSSSSSSSSSS\n";
73 
74  uint32_t crc_error_counter = 0;
75  uint32_t RxState;
76  uint32_t RxError;
77 
78  void mount_disk(void) const;
79  void unmount_disk(void) const;
81 
82  enum sbf_ids {
83  DOP = 4001,
84  PVTGeodetic = 4007,
88  };
89 
90  struct PACKED msg4007 // PVTGeodetic
91  {
92  uint32_t TOW;
93  uint16_t WNc;
94  uint8_t Mode;
95  uint8_t Error;
96  double Latitude;
97  double Longitude;
98  double Height;
99  float Undulation;
100  float Vn;
101  float Ve;
102  float Vu;
103  float COG;
104  double RxClkBias;
105  float RxClkDrift;
106  uint8_t TimeSystem;
107  uint8_t Datum;
108  uint8_t NrSV;
109  uint8_t WACorrInfo;
110  uint16_t ReferenceID;
111  uint16_t MeanCorrAge;
112  uint32_t SignalInfo;
113  uint8_t AlertFlag;
114  // rev1
115  uint8_t NrBases;
116  uint16_t PPPInfo;
117  // rev2
118  uint16_t Latency;
119  uint16_t HAccuracy;
120  uint16_t VAccuracy;
121  uint8_t Misc;
122  };
123 
124  struct PACKED msg4001 // DOP
125  {
126  uint32_t TOW;
127  uint16_t WNc;
128  uint8_t NrSV;
129  uint8_t Reserved;
130  uint16_t PDOP;
131  uint16_t TDOP;
132  uint16_t HDOP;
133  uint16_t VDOP;
134  float HPL;
135  float VPL;
136  };
137 
138  struct PACKED msg4014 // ReceiverStatus (v2)
139  {
140  uint32_t TOW;
141  uint16_t WNc;
142  uint8_t CPULoad;
143  uint8_t ExtError;
144  uint32_t UpTime;
145  uint32_t RxState;
146  uint32_t RxError;
147  // remaining data is AGCData, which we don't have a use for, don't extract the data
148  };
149 
150  struct PACKED msg5908 // VelCovGeodetic
151  {
152  uint32_t TOW;
153  uint16_t WNc;
154  uint8_t Mode;
155  uint8_t Error;
156  float Cov_VnVn;
157  float Cov_VeVe;
158  float Cov_VuVu;
159  float Cov_DtDt;
160  float Cov_VnVe;
161  float Cov_VnVu;
162  float Cov_VnDt;
163  float Cov_VeVu;
164  float Cov_VeDt;
165  float Cov_VuDt;
166  };
167 
173  uint8_t bytes[256];
174  };
175 
177  {
178  enum
179  {
180  PREAMBLE1 = 0,
189  COMMAND_LINE // used to parse command responses
190  } sbf_state;
191  uint16_t preamble;
192  uint16_t crc;
193  uint16_t blockid;
194  uint16_t length;
196  uint16_t read;
197  } sbf_msg;
198 
199  void log_ExtEventPVTGeodetic(const msg4007 &temp);
200 
201  enum {
202  SOFTWARE = (1 << 3), // set upon detection of a software warning or error. This bit is reset by the command “lif, error”
203  WATCHDOG = (1 << 4), // set when the watch-dog expired at least once since the last power-on.
204  CONGESTION = (1 << 6), // set when an output data congestion has been detected on at least one of the communication ports of the receiver during the last second.
205  MISSEDEVENT = (1 << 8), // set when an external event congestion has been detected during the last second. It indicates that the receiver is receiving too many events on its EVENTx pins.
206  CPUOVERLOAD = (1 << 9), // set when the CPU load is larger than 90%. If this bit is set, receiver operation may be unreliable and the user must decrease the processing load by following the recommendations in the User Manual.
207  INVALIDCONFIG = (1 << 10), // set if one or more configuration file (permission or channel configuration) is invalid or absent.
208  OUTOFGEOFENCE = (1 << 11), // set if the receiver is currently out of its permitted region of operation (geo-fencing).
209  };
210 };
Definition: AP_GPS.h:48
const char * _initialisation_blob[5]
Definition: AP_GPS_SBF.h:64
uint16_t MeanCorrAge
Definition: AP_GPS_SBF.h:111
uint16_t ReferenceID
Definition: AP_GPS_SBF.h:110
const char * _port_enable
Definition: AP_GPS_SBF.h:72
uint8_t _init_blob_index
Definition: AP_GPS_SBF.h:62
struct AP_GPS_SBF::sbf_msg_parser_t sbf_msg
uint32_t RxState
Definition: AP_GPS_SBF.h:75
const char * name() const override
Definition: AP_GPS_SBF.h:40
bool process_message()
Definition: AP_GPS_SBF.cpp:267
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
void log_ExtEventPVTGeodetic(const msg4007 &temp)
Definition: AP_GPS_SBF.cpp:238
uint32_t crc_error_counter
Definition: AP_GPS_SBF.h:74
void mount_disk(void) const
Definition: AP_GPS_SBF.cpp:417
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_SBF.h:35
bool parse(uint8_t temp)
Definition: AP_GPS_SBF.cpp:111
AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBF.cpp:53
void unmount_disk(void) const
Definition: AP_GPS_SBF.cpp:423
bool _has_been_armed
Definition: AP_GPS_SBF.h:80
bool read()
Definition: AP_GPS_SBF.cpp:66
uint32_t _init_blob_time
Definition: AP_GPS_SBF.h:63
bool is_configured(void) override
Definition: AP_GPS_SBF.cpp:408
static const uint8_t SBF_PREAMBLE1
Definition: AP_GPS_SBF.h:59
#define PACKED
Definition: AP_Common.h:28
void broadcast_configuration_failure_reason(void) const override
Definition: AP_GPS_SBF.cpp:399
static const uint8_t SBF_PREAMBLE2
Definition: AP_GPS_SBF.h:60
bool get_lag(float &lag_sec) const override
Definition: AP_GPS_SBF.h:47
uint32_t RxError
Definition: AP_GPS_SBF.h:76
uint32_t _config_last_ack_time
Definition: AP_GPS_SBF.h:70
bool prepare_for_arming(void) override
Definition: AP_GPS_SBF.cpp:429
bool is_healthy(void) const override
Definition: AP_GPS_SBF.cpp:413