APM:Libraries
AP_GPS_NOVA.cpp
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 #include "AP_GPS.h"
21 #include "AP_GPS_NOVA.h"
22 #include <DataFlash/DataFlash.h>
23 
24 extern const AP_HAL::HAL& hal;
25 
26 #define NOVA_DEBUGGING 0
27 
28 #if NOVA_DEBUGGING
29 #include <cstdio>
30  # define Debug(fmt, args ...) \
31 do { \
32  printf("%s:%d: " fmt "\n", \
33  __FUNCTION__, __LINE__, \
34  ## args); \
35  hal.scheduler->delay(1); \
36 } while(0)
37 #else
38  # define Debug(fmt, args ...)
39 #endif
40 
42  AP_HAL::UARTDriver *_port) :
43  AP_GPS_Backend(_gps, _state, _port)
44 {
46 
47  const char *init_str = _initialisation_blob[0];
48  const char *init_str1 = _initialisation_blob[1];
49 
50  port->write((const uint8_t*)init_str, strlen(init_str));
51  port->write((const uint8_t*)init_str1, strlen(init_str1));
52 }
53 
54 // Process all bytes available from the stream
55 //
56 bool
58 {
59  uint32_t now = AP_HAL::millis();
60 
61  if (_init_blob_index < (sizeof(_initialisation_blob) / sizeof(_initialisation_blob[0]))) {
62  const char *init_str = _initialisation_blob[_init_blob_index];
63 
64  if (now > _init_blob_time) {
65  port->write((const uint8_t*)init_str, strlen(init_str));
66  _init_blob_time = now + 200;
68  }
69  }
70 
71  bool ret = false;
72  while (port->available() > 0) {
73  uint8_t temp = port->read();
74  ret |= parse(temp);
75  }
76 
77  return ret;
78 }
79 
80 bool
81 AP_GPS_NOVA::parse(uint8_t temp)
82 {
83  switch (nova_msg.nova_state)
84  {
85  default:
87  if (temp == NOVA_PREAMBLE1)
89  nova_msg.read = 0;
90  break;
92  if (temp == NOVA_PREAMBLE2)
93  {
95  }
96  else
97  {
99  }
100  break;
102  if (temp == NOVA_PREAMBLE3)
103  {
105  }
106  else
107  {
109  }
110  break;
112  Debug("NOVA HEADERLENGTH\n");
116  nova_msg.header.data[3] = temp;
119  nova_msg.read = 4;
120  break;
122  if (nova_msg.read >= sizeof(nova_msg.header.data)) {
123  Debug("parse header overflow length=%u\n", (unsigned)nova_msg.read);
125  break;
126  }
127  nova_msg.header.data[nova_msg.read] = temp;
128  nova_msg.read++;
130  {
132  }
133  break;
135  if (nova_msg.read >= sizeof(nova_msg.data)) {
136  Debug("parse data overflow length=%u msglength=%u\n", (unsigned)nova_msg.read,nova_msg.header.nova_headeru.messagelength);
138  break;
139  }
141  nova_msg.read++;
143  {
144  Debug("NOVA DATA exit\n");
146  }
147  break;
149  nova_msg.crc = (uint32_t) (temp << 0);
151  break;
153  nova_msg.crc += (uint32_t) (temp << 8);
155  break;
157  nova_msg.crc += (uint32_t) (temp << 16);
159  break;
161  nova_msg.crc += (uint32_t) (temp << 24);
163 
164  uint32_t crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.headerlength, (uint8_t *)&nova_msg.header.data, (uint32_t)0);
165  crc = CalculateBlockCRC32((uint32_t)nova_msg.header.nova_headeru.messagelength, (uint8_t *)&nova_msg.data, crc);
166 
167  if (nova_msg.crc == crc)
168  {
169  return process_message();
170  }
171  else
172  {
173  Debug("crc failed");
175  }
176  break;
177  }
178 
179  return false;
180 }
181 
182 bool
184 {
185  uint16_t messageid = nova_msg.header.nova_headeru.messageid;
186 
187  Debug("NOVA process_message messid=%u\n",messageid);
188 
189  if (messageid == 42) // bestpos
190  {
191  const bestpos &bestposu = nova_msg.data.bestposu;
192 
196 
197  state.location.lat = (int32_t) (bestposu.lat * (double)1e7);
198  state.location.lng = (int32_t) (bestposu.lng * (double)1e7);
199  state.location.alt = (int32_t) (bestposu.hgt * 100);
200 
201  state.num_sats = bestposu.svsused;
202 
203  state.horizontal_accuracy = (float) ((bestposu.latsdev + bestposu.lngsdev)/2);
204  state.vertical_accuracy = (float) bestposu.hgtsdev;
207  state.rtk_age_ms = bestposu.diffage * 1000;
208  state.rtk_num_sats = bestposu.svsused;
209 
210  if (bestposu.solstat == 0) // have a solution
211  {
212  switch (bestposu.postype)
213  {
214  case 16:
216  break;
217  case 17: // psrdiff
218  case 18: // waas
219  case 20: // omnistar
220  case 68: // ppp_converg
221  case 69: // ppp
223  break;
224  case 32: // l1 float
225  case 33: // iono float
226  case 34: // narrow float
228  break;
229  case 48: // l1 int
230  case 50: // narrow int
232  break;
233  case 0: // NONE
234  case 1: // FIXEDPOS
235  case 2: // FIXEDHEIGHT
236  default:
238  break;
239  }
240  }
241  else
242  {
244  }
245 
246  _new_position = true;
247  }
248 
249  if (messageid == 99) // bestvel
250  {
251  const bestvel &bestvelu = nova_msg.data.bestvelu;
252 
253  state.ground_speed = (float) bestvelu.horspd;
254  state.ground_course = (float) bestvelu.trkgnd;
256  state.velocity.z = -(float) bestvelu.vertspd;
258 
260  _new_speed = true;
261  }
262 
263  if (messageid == 174) // psrdop
264  {
265  const psrdop &psrdopu = nova_msg.data.psrdopu;
266 
267  state.hdop = (uint16_t) (psrdopu.hdop*100);
268  state.vdop = (uint16_t) (psrdopu.htdop*100);
269  return false;
270  }
271 
272  // ensure out position and velocity stay insync
274  _new_speed = _new_position = false;
275 
276  return true;
277  }
278 
279  return false;
280 }
281 
282 void
283 AP_GPS_NOVA::inject_data(const uint8_t *data, uint16_t len)
284 {
285  if (port->txspace() > len) {
287  port->write(data, len);
288  } else {
289  Debug("NOVA: Not enough TXSPACE");
290  }
291 }
292 
293 #define CRC32_POLYNOMIAL 0xEDB88320L
294 uint32_t AP_GPS_NOVA::CRC32Value(uint32_t icrc)
295 {
296  int i;
297  uint32_t crc = icrc;
298  for ( i = 8 ; i > 0; i-- )
299  {
300  if ( crc & 1 )
301  crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL;
302  else
303  crc >>= 1;
304  }
305  return crc;
306 }
307 
308 uint32_t AP_GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
309 {
310  while ( length-- != 0 )
311  {
312  crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff));
313  }
314  return( crc );
315 }
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
uint8_t _init_blob_index
Definition: AP_GPS_NOVA.h:57
uint32_t solstat
Solution status.
Definition: AP_GPS_NOVA.h:117
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
static const uint8_t NOVA_PREAMBLE1
Definition: AP_GPS_NOVA.h:46
float latsdev
latitude standard deviation (m)
Definition: AP_GPS_NOVA.h:124
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
bool parse(uint8_t temp)
Definition: AP_GPS_NOVA.cpp:81
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_NOVA.cpp:41
#define CRC32_POLYNOMIAL
struct PACKED AP_GPS_NOVA::nova_msg_parser nova_msg
virtual uint32_t txspace()=0
#define Debug(fmt, args ...)
Definition: AP_GPS_NOVA.cpp:38
float lngsdev
longitude standard deviation (m)
Definition: AP_GPS_NOVA.h:125
enum AP_GPS_NOVA::nova_msg_parser::@30 nova_state
uint32_t postype
Position type.
Definition: AP_GPS_NOVA.h:118
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint32_t _last_vel_time
Definition: AP_GPS_NOVA.h:55
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void inject_data(const uint8_t *data, uint16_t len) override
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
nova_header nova_headeru
Definition: AP_GPS_NOVA.h:162
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Definition: AP_GPS.h:155
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
T z
Definition: vector3.h:67
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
Definition: AP_GPS.h:154
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
uint32_t _init_blob_time
Definition: AP_GPS_NOVA.h:58
virtual int16_t read()=0
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)
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void fill_3d_velocity(void)
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
double hgt
height above mean sea level (m)
Definition: AP_GPS_NOVA.h:121
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
bool _new_speed
Definition: AP_GPS_NOVA.h:53
static const uint8_t NOVA_PREAMBLE3
Definition: AP_GPS_NOVA.h:48
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float horizontal_accuracy
horizontal RMS accuracy estimate in m
Definition: AP_GPS.h:143
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
double lng
longitude (deg)
Definition: AP_GPS_NOVA.h:120
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
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
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
float diffage
differential position age (sec)
Definition: AP_GPS_NOVA.h:129
bool process_message()
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
float ground_course
ground course in degrees
Definition: AP_GPS.h:137
bool _new_position
Definition: AP_GPS_NOVA.h:51