APM:Libraries
AP_GPS_NOVA.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 // Novatel/Tersus/ComNav GPS driver for ArduPilot.
17 // Code by Michael Oborne
18 // Derived from http://www.novatel.com/assets/Documents/Manuals/om-20000129.pdf
19 
20 #pragma once
21 
22 #include "AP_GPS.h"
23 #include "GPS_Backend.h"
24 
26 {
27 public:
29 
31 
32  // Methods
33  bool read();
34 
35  void inject_data(const uint8_t *data, uint16_t len) override;
36 
37  const char *name() const override { return "NOVA"; }
38 
39 private:
40 
41  bool parse(uint8_t temp);
42  bool process_message();
43  uint32_t CRC32Value(uint32_t icrc);
44  uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc);
45 
46  static const uint8_t NOVA_PREAMBLE1 = 0xaa;
47  static const uint8_t NOVA_PREAMBLE2 = 0x44;
48  static const uint8_t NOVA_PREAMBLE3 = 0x12;
49 
50  // do we have new position information?
51  bool _new_position:1;
52  // do we have new speed information?
53  bool _new_speed:1;
54 
55  uint32_t _last_vel_time;
56 
57  uint8_t _init_blob_index = 0;
58  uint32_t _init_blob_time = 0;
59  const char* _initialisation_blob[6] = {
60  "\r\n\r\nunlogall\r\n", // cleanup enviroment
61  "log bestposb ontime 0.2 0 nohold\r\n", // get bestpos
62  "log bestvelb ontime 0.2 0 nohold\r\n", // get bestvel
63  "log psrdopb onchanged\r\n", // tersus
64  "log psrdopb ontime 0.2\r\n", // comnav
65  "log psrdopb\r\n" // poll message, as dop only changes when a sat is dropped/added to the visible list
66  };
67 
68  uint32_t crc_error_counter = 0;
69  uint32_t last_injected_data_ms = 0;
70 
72  {
73  // 0
74  uint8_t preamble[3];
75  // 3
76  uint8_t headerlength;
77  // 4
78  uint16_t messageid;
79  // 6
80  uint8_t messagetype;
81  //7
82  uint8_t portaddr;
83  //8
84  uint16_t messagelength;
85  //10
86  uint16_t sequence;
87  //12
88  uint8_t idletime;
89  //13
90  uint8_t timestatus;
91  //14
92  uint16_t week;
93  //16
94  uint32_t tow;
95  //20
96  uint32_t recvstatus;
97  // 24
98  uint16_t resv;
99  //26
100  uint16_t recvswver;
101  };
102 
103  struct PACKED psrdop
104  {
105  float gdop;
106  float pdop;
107  float hdop;
108  float htdop;
109  float tdop;
110  float cutoff;
111  uint32_t svcount;
112  // extra data for individual prns
113  };
114 
116  {
117  uint32_t solstat;
118  uint32_t postype;
119  double lat;
120  double lng;
121  double hgt;
122  float undulation;
123  uint32_t datumid;
124  float latsdev;
125  float lngsdev;
126  float hgtsdev;
127  // 4 bytes
128  uint8_t stnid[4];
129  float diffage;
130  float sol_age;
131  uint8_t svstracked;
132  uint8_t svsused;
133  uint8_t svsl1;
134  uint8_t svsmultfreq;
135  uint8_t resv;
136  uint8_t extsolstat;
137  uint8_t galbeisigmask;
138  uint8_t gpsglosigmask;
139  };
140 
142  {
143  uint32_t solstat;
144  uint32_t veltype;
145  float latency;
146  float age;
147  double horspd;
148  double trkgnd;
149  // + up
150  double vertspd;
151  float resv;
152  };
153 
158  uint8_t bytes[256];
159  };
160 
163  uint8_t data[28];
164  };
165 
167  {
168  enum
169  {
170  PREAMBLE1 = 0,
180  } nova_state;
181 
183  uint32_t crc;
185  uint16_t read;
186  } nova_msg;
187 };
Definition: AP_GPS.h:48
uint8_t _init_blob_index
Definition: AP_GPS_NOVA.h:57
uint32_t solstat
Solution status.
Definition: AP_GPS_NOVA.h:117
static const uint8_t NOVA_PREAMBLE1
Definition: AP_GPS_NOVA.h:46
float latsdev
latitude standard deviation (m)
Definition: AP_GPS_NOVA.h:124
float sol_age
solution age (sec)
Definition: AP_GPS_NOVA.h:130
bool parse(uint8_t temp)
Definition: AP_GPS_NOVA.cpp:81
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_NOVA.cpp:41
uint8_t extsolstat
extended solution status - OEMV and greater only
Definition: AP_GPS_NOVA.h:136
struct PACKED AP_GPS_NOVA::nova_msg_parser nova_msg
float lngsdev
longitude standard deviation (m)
Definition: AP_GPS_NOVA.h:125
uint32_t postype
Position type.
Definition: AP_GPS_NOVA.h:118
uint32_t _last_vel_time
Definition: AP_GPS_NOVA.h:55
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
float undulation
relationship between the geoid and the ellipsoid (m)
Definition: AP_GPS_NOVA.h:122
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
void inject_data(const uint8_t *data, uint16_t len) override
nova_header nova_headeru
Definition: AP_GPS_NOVA.h:162
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
uint32_t datumid
datum id number
Definition: AP_GPS_NOVA.h:123
uint32_t _init_blob_time
Definition: AP_GPS_NOVA.h:58
uint32_t crc_error_counter
Definition: AP_GPS_NOVA.h:68
float hgtsdev
height standard deviation (m)
Definition: AP_GPS_NOVA.h:126
uint8_t svsused
number of satellites used in solution
Definition: AP_GPS_NOVA.h:132
static const uint8_t NOVA_PREAMBLE2
Definition: AP_GPS_NOVA.h:47
uint32_t CRC32Value(uint32_t icrc)
uint8_t svstracked
number of satellites tracked
Definition: AP_GPS_NOVA.h:131
uint8_t resv
reserved
Definition: AP_GPS_NOVA.h:135
double hgt
height above mean sea level (m)
Definition: AP_GPS_NOVA.h:121
#define PACKED
Definition: AP_Common.h:28
uint8_t svsmultfreq
number of GPS plus GLONASS L2 satellites used in solution
Definition: AP_GPS_NOVA.h:134
const char * name() const override
Definition: AP_GPS_NOVA.h:37
uint8_t svsl1
number of GPS plus GLONASS L1 satellites used in solution
Definition: AP_GPS_NOVA.h:133
bool _new_speed
Definition: AP_GPS_NOVA.h:53
static const uint8_t NOVA_PREAMBLE3
Definition: AP_GPS_NOVA.h:48
double lng
longitude (deg)
Definition: AP_GPS_NOVA.h:120
double lat
latitude (deg)
Definition: AP_GPS_NOVA.h:119
uint32_t last_injected_data_ms
Definition: AP_GPS_NOVA.h:69
const char * _initialisation_blob[6]
Definition: AP_GPS_NOVA.h:59
float diffage
differential position age (sec)
Definition: AP_GPS_NOVA.h:129
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_NOVA.h:30
bool process_message()
bool _new_position
Definition: AP_GPS_NOVA.h:51