APM:Libraries
sitl_gps.cpp
Go to the documentation of this file.
1 /*
2  SITL handling
3 
4  This simulates a GPS on a serial port
5 
6  Andrew Tridgell November 2011
7  */
8 
9 #include <AP_HAL/AP_HAL.h>
10 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
11 
12 #include "AP_HAL_SITL.h"
13 #include "AP_HAL_SITL_Namespace.h"
14 #include "HAL_SITL_Class.h"
15 
16 #include <AP_Math/AP_Math.h>
17 #include <SITL/SITL.h>
18 #include "Scheduler.h"
19 #include "UARTDriver.h"
20 #include <AP_GPS/AP_GPS.h>
21 #include <AP_GPS/AP_GPS_UBLOX.h>
22 #include <sys/ioctl.h>
23 #include <unistd.h>
24 #include <time.h>
25 #include <stdio.h>
26 #include <sys/time.h>
27 #include <sys/stat.h>
28 #include <sys/types.h>
29 #include <fcntl.h>
30 
31 #pragma GCC diagnostic ignored "-Wunused-result"
32 
33 using namespace HALSITL;
34 extern const AP_HAL::HAL& hal;
35 
36 static uint8_t next_gps_index;
37 static uint8_t gps_delay;
38 
39 // state of GPS emulation
40 static struct gps_state {
41  /* pipe emulating UBLOX GPS serial stream */
42  int gps_fd, client_fd;
43  uint32_t last_update; // milliseconds
45 
46 /*
47  hook for reading from the GPS pipe
48  */
49 ssize_t SITL_State::gps_read(int fd, void *buf, size_t count)
50 {
51 #ifdef FIONREAD
52  // use FIONREAD to get exact value if possible
53  int num_ready;
54  while (ioctl(fd, FIONREAD, &num_ready) == 0 && num_ready > 3000) {
55  // the pipe is filling up - drain it
56  uint8_t tmp[128];
57  if (read(fd, tmp, sizeof(tmp)) != sizeof(tmp)) {
58  break;
59  }
60  }
61 #endif
62  return read(fd, buf, count);
63 }
64 
65 /*
66  setup GPS input pipe
67  */
69 {
70  int fd[2];
71  if (gps_state.client_fd != 0) {
72  return gps_state.client_fd;
73  }
74  pipe(fd);
75  gps_state.gps_fd = fd[1];
76  gps_state.client_fd = fd[0];
80  return gps_state.client_fd;
81 }
82 
83 /*
84  setup GPS2 input pipe
85  */
87 {
88  int fd[2];
89  if (gps2_state.client_fd != 0) {
90  return gps2_state.client_fd;
91  }
92  pipe(fd);
93  gps2_state.gps_fd = fd[1];
94  gps2_state.client_fd = fd[0];
95  gps2_state.last_update = AP_HAL::millis();
98  return gps2_state.client_fd;
99 }
100 
101 /*
102  write some bytes from the simulated GPS
103  */
104 void SITL_State::_gps_write(const uint8_t *p, uint16_t size, uint8_t instance)
105 {
106  while (size--) {
107  if (_sitl->gps_byteloss > 0.0f) {
108  float r = ((((unsigned)random()) % 1000000)) / 1.0e4;
109  if (r < _sitl->gps_byteloss) {
110  // lose the byte
111  p++;
112  continue;
113  }
114  }
115  if (instance == 0 && gps_state.gps_fd != 0) {
116  write(gps_state.gps_fd, p, 1);
117  }
118  if (instance == 1 && _sitl->gps2_enable) {
119  if (gps2_state.gps_fd != 0) {
120  write(gps2_state.gps_fd, p, 1);
121  }
122  }
123  p++;
124  }
125 }
126 
127 /*
128  get timeval using simulation time
129  */
130 static void simulation_timeval(struct timeval *tv)
131 {
132  uint64_t now = AP_HAL::micros64();
133  static uint64_t first_usec;
134  static struct timeval first_tv;
135  if (first_usec == 0) {
136  first_usec = now;
137  gettimeofday(&first_tv, nullptr);
138  }
139  *tv = first_tv;
140  tv->tv_sec += now / 1000000ULL;
141  uint64_t new_usec = tv->tv_usec + (now % 1000000ULL);
142  tv->tv_sec += new_usec / 1000000ULL;
143  tv->tv_usec = new_usec % 1000000ULL;
144 }
145 
146 /*
147  send a UBLOX GPS message
148  */
149 void SITL_State::_gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance)
150 {
151  const uint8_t PREAMBLE1 = 0xb5;
152  const uint8_t PREAMBLE2 = 0x62;
153  const uint8_t CLASS_NAV = 0x1;
154  uint8_t hdr[6], chk[2];
155  hdr[0] = PREAMBLE1;
156  hdr[1] = PREAMBLE2;
157  hdr[2] = CLASS_NAV;
158  hdr[3] = msgid;
159  hdr[4] = size & 0xFF;
160  hdr[5] = size >> 8;
161  chk[0] = chk[1] = hdr[2];
162  chk[1] += (chk[0] += hdr[3]);
163  chk[1] += (chk[0] += hdr[4]);
164  chk[1] += (chk[0] += hdr[5]);
165  for (uint8_t i=0; i<size; i++) {
166  chk[1] += (chk[0] += buf[i]);
167  }
168  _gps_write(hdr, sizeof(hdr), instance);
169  _gps_write(buf, size, instance);
170  _gps_write(chk, sizeof(chk), instance);
171 }
172 
173 /*
174  return GPS time of week in milliseconds
175  */
176 static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
177 {
178  struct timeval tv;
179  simulation_timeval(&tv);
180  const uint32_t epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2) - (GPS_LEAPSECONDS_MILLIS / 1000ULL);
181  uint32_t epoch_seconds = tv.tv_sec - epoch;
182  *time_week = epoch_seconds / AP_SEC_PER_WEEK;
183  uint32_t t_ms = tv.tv_usec / 1000;
184  // round time to nearest 200ms
185  *time_week_ms = (epoch_seconds % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC + ((t_ms/200) * 200);
186 }
187 
188 /*
189  send a new set of GPS UBLOX packets
190  */
191 void SITL_State::_update_gps_ubx(const struct gps_data *d, uint8_t instance)
192 {
193  struct PACKED ubx_nav_posllh {
194  uint32_t time; // GPS msToW
195  int32_t longitude;
196  int32_t latitude;
197  int32_t altitude_ellipsoid;
198  int32_t altitude_msl;
199  uint32_t horizontal_accuracy;
200  uint32_t vertical_accuracy;
201  } pos {};
202  struct PACKED ubx_nav_status {
203  uint32_t time; // GPS msToW
204  uint8_t fix_type;
205  uint8_t fix_status;
206  uint8_t differential_status;
207  uint8_t res;
208  uint32_t time_to_first_fix;
209  uint32_t uptime; // milliseconds
210  } status {};
211  struct PACKED ubx_nav_velned {
212  uint32_t time; // GPS msToW
213  int32_t ned_north;
214  int32_t ned_east;
215  int32_t ned_down;
216  uint32_t speed_3d;
217  uint32_t speed_2d;
218  int32_t heading_2d;
219  uint32_t speed_accuracy;
220  uint32_t heading_accuracy;
221  } velned {};
222  struct PACKED ubx_nav_solution {
223  uint32_t time;
224  int32_t time_nsec;
225  int16_t week;
226  uint8_t fix_type;
227  uint8_t fix_status;
228  int32_t ecef_x;
229  int32_t ecef_y;
230  int32_t ecef_z;
231  uint32_t position_accuracy_3d;
232  int32_t ecef_x_velocity;
233  int32_t ecef_y_velocity;
234  int32_t ecef_z_velocity;
235  uint32_t speed_accuracy;
236  uint16_t position_DOP;
237  uint8_t res;
238  uint8_t satellites;
239  uint32_t res2;
240  } sol {};
241  struct PACKED ubx_nav_dop {
242  uint32_t time; // GPS msToW
243  uint16_t gDOP;
244  uint16_t pDOP;
245  uint16_t tDOP;
246  uint16_t vDOP;
247  uint16_t hDOP;
248  uint16_t nDOP;
249  uint16_t eDOP;
250  } dop {};
251  struct PACKED ubx_nav_pvt {
252  uint32_t itow;
253  uint16_t year;
254  uint8_t month, day, hour, min, sec;
255  uint8_t valid;
256  uint32_t t_acc;
257  int32_t nano;
258  uint8_t fix_type;
259  uint8_t flags;
260  uint8_t flags2;
261  uint8_t num_sv;
262  int32_t lon, lat;
263  int32_t height, h_msl;
264  uint32_t h_acc, v_acc;
265  int32_t velN, velE, velD, gspeed;
266  int32_t head_mot;
267  uint32_t s_acc;
268  uint32_t head_acc;
269  uint16_t p_dop;
270  uint8_t reserved1[6];
271  uint32_t headVeh;
272  uint8_t reserved2[4];
273  } pvt {};
274  const uint8_t SV_COUNT = 10;
275  struct PACKED ubx_nav_svinfo {
276  uint32_t itow;
277  uint8_t numCh;
278  uint8_t globalFlags;
279  uint8_t reserved1[2];
280  // repeated block
281  struct PACKED svinfo_sv {
282  uint8_t chn;
283  uint8_t svid;
284  uint8_t flags;
285  uint8_t quality;
286  uint8_t cno;
287  int8_t elev;
288  int16_t azim;
289  int32_t prRes;
290  } sv[SV_COUNT];
291  } svinfo {};
292  const uint8_t MSG_POSLLH = 0x2;
293  const uint8_t MSG_STATUS = 0x3;
294  const uint8_t MSG_DOP = 0x4;
295  const uint8_t MSG_VELNED = 0x12;
296  const uint8_t MSG_SOL = 0x6;
297  const uint8_t MSG_PVT = 0x7;
298  const uint8_t MSG_SVINFO = 0x30;
299 
300  static uint32_t _next_nav_sv_info_time = 0;
301 
302  uint16_t time_week;
303  uint32_t time_week_ms;
304 
305  gps_time(&time_week, &time_week_ms);
306 
307  pos.time = time_week_ms;
308  pos.longitude = d->longitude * 1.0e7;
309  pos.latitude = d->latitude * 1.0e7;
310  pos.altitude_ellipsoid = d->altitude * 1000.0f;
311  pos.altitude_msl = d->altitude * 1000.0f;
312  pos.horizontal_accuracy = 1500;
313  pos.vertical_accuracy = 2000;
314 
315  status.time = time_week_ms;
316  status.fix_type = d->have_lock?3:0;
317  status.fix_status = d->have_lock?1:0;
318  status.differential_status = 0;
319  status.res = 0;
320  status.time_to_first_fix = 0;
321  status.uptime = AP_HAL::millis();
322 
323  velned.time = time_week_ms;
324  velned.ned_north = 100.0f * d->speedN;
325  velned.ned_east = 100.0f * d->speedE;
326  velned.ned_down = 100.0f * d->speedD;
327  velned.speed_2d = norm(d->speedN, d->speedE) * 100;
328  velned.speed_3d = norm(d->speedN, d->speedE, d->speedD) * 100;
329  velned.heading_2d = ToDeg(atan2f(d->speedE, d->speedN)) * 100000.0f;
330  if (velned.heading_2d < 0.0f) {
331  velned.heading_2d += 360.0f * 100000.0f;
332  }
333  velned.speed_accuracy = 40;
334  velned.heading_accuracy = 4;
335 
336  memset(&sol, 0, sizeof(sol));
337  sol.fix_type = d->have_lock?3:0;
338  sol.fix_status = 221;
339  sol.satellites = d->have_lock?_sitl->gps_numsats:3;
340  sol.time = time_week_ms;
341  sol.week = time_week;
342 
343  dop.time = time_week_ms;
344  dop.gDOP = 65535;
345  dop.pDOP = 65535;
346  dop.tDOP = 65535;
347  dop.vDOP = 200;
348  dop.hDOP = 121;
349  dop.nDOP = 65535;
350  dop.eDOP = 65535;
351 
352  pvt.itow = time_week_ms;
353  pvt.year = 0;
354  pvt.month = 0;
355  pvt.day = 0;
356  pvt.hour = 0;
357  pvt.min = 0;
358  pvt.sec = 0;
359  pvt.valid = 0; // invalid utc date
360  pvt.t_acc = 0;
361  pvt.nano = 0;
362  pvt.fix_type = d->have_lock? 0x3 : 0;
363  pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok
364  pvt.flags2 =0;
365  pvt.num_sv = d->have_lock?_sitl->gps_numsats:3;
366  pvt.lon = d->longitude * 1.0e7;
367  pvt.lat = d->latitude * 1.0e7;
368  pvt.height = d->altitude * 1000.0f;
369  pvt.h_msl = d->altitude * 1000.0f;
370  pvt.h_acc = 200;
371  pvt.v_acc = 200;
372  pvt.velN = 1000.0f * d->speedN;
373  pvt.velE = 1000.0f * d->speedE;
374  pvt.velD = 1000.0f * d->speedD;
375  pvt.gspeed = norm(d->speedN, d->speedE) * 1000;
376  pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5;
377  pvt.s_acc = 40;
378  pvt.head_acc = 38 * 1.0e5;
379  pvt.p_dop = 65535;
380  memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1));
381  pvt.headVeh = 0;
382  memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2));
383 
384  _gps_send_ubx(MSG_POSLLH, (uint8_t*)&pos, sizeof(pos), instance);
385  _gps_send_ubx(MSG_STATUS, (uint8_t*)&status, sizeof(status), instance);
386  _gps_send_ubx(MSG_VELNED, (uint8_t*)&velned, sizeof(velned), instance);
387  _gps_send_ubx(MSG_SOL, (uint8_t*)&sol, sizeof(sol), instance);
388  _gps_send_ubx(MSG_DOP, (uint8_t*)&dop, sizeof(dop), instance);
389  _gps_send_ubx(MSG_PVT, (uint8_t*)&pvt, sizeof(pvt), instance);
390 
391  if (time_week_ms > _next_nav_sv_info_time) {
392  svinfo.itow = time_week_ms;
393  svinfo.numCh = 32;
394  svinfo.globalFlags = 4; // u-blox 8/M8
395  // fill in the SV's with some data even though firmware does not currently use it
396  // note that this is not using num_sats as we aren't dynamically creating this to match
397  for (uint8_t i = 0; i < SV_COUNT; i++) {
398  svinfo.sv[i].chn = i;
399  svinfo.sv[i].svid = i;
400  svinfo.sv[i].flags = (i < _sitl->gps_numsats) ? 0x7 : 0x6; // sv used, diff correction data, orbit information
401  svinfo.sv[i].quality = 7; // code and carrier lock and time synchronized
402  svinfo.sv[i].cno = MAX(20, 30 - i);
403  svinfo.sv[i].elev = MAX(30, 90 - i);
404  svinfo.sv[i].azim = i;
405  // not bothering to fill in prRes
406  }
407  _gps_send_ubx(MSG_SVINFO, (uint8_t*)&svinfo, sizeof(svinfo), instance);
408  _next_nav_sv_info_time = time_week_ms + 10000; // 10 second delay
409  }
410 }
411 
412 static void swap_uint32(uint32_t *v, uint8_t n)
413 {
414  while (n--) {
415  *v = htonl(*v);
416  v++;
417  }
418 }
419 
420 /*
421  MTK type simple checksum
422  */
423 static void mtk_checksum(const uint8_t *data, uint8_t n, uint8_t *ck_a, uint8_t *ck_b)
424 {
425  *ck_a = *ck_b = 0;
426  while (n--) {
427  *ck_a += *data++;
428  *ck_b += *ck_a;
429  }
430 }
431 
432 
433 /*
434  send a new GPS MTK packet
435  */
436 void SITL_State::_update_gps_mtk(const struct gps_data *d, uint8_t instance)
437 {
438  struct PACKED mtk_msg {
439  uint8_t preamble1;
440  uint8_t preamble2;
441  uint8_t msg_class;
442  uint8_t msg_id;
443  int32_t latitude;
444  int32_t longitude;
445  int32_t altitude;
446  int32_t ground_speed;
447  int32_t ground_course;
448  uint8_t satellites;
449  uint8_t fix_type;
450  uint32_t utc_time;
451  uint8_t ck_a;
452  uint8_t ck_b;
453  } p;
454 
455  p.preamble1 = 0xb5;
456  p.preamble2 = 0x62;
457  p.msg_class = 1;
458  p.msg_id = 5;
459  p.latitude = d->latitude * 1.0e6;
460  p.longitude = d->longitude * 1.0e6;
461  p.altitude = d->altitude * 100;
462  p.ground_speed = norm(d->speedN, d->speedE) * 100;
463  p.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 1000000.0f;
464  if (p.ground_course < 0.0f) {
465  p.ground_course += 360.0f * 1000000.0f;
466  }
467  p.satellites = d->have_lock?_sitl->gps_numsats:3;
468  p.fix_type = d->have_lock?3:1;
469 
470  // the spec is not very clear, but the time field seems to be
471  // milliseconds since the start of the day in UTC time,
472  // done in powers of 100.
473  // The date is powers of 100 as well, but in days since 1/1/2000
474  struct tm tm;
475  struct timeval tv;
476 
477  simulation_timeval(&tv);
478  tm = *gmtime(&tv.tv_sec);
479  uint32_t hsec = (tv.tv_usec / (10000*20)) * 20; // always multiple of 20
480 
481  p.utc_time = hsec + tm.tm_sec*100 + tm.tm_min*100*100 + tm.tm_hour*100*100*100;
482 
483  swap_uint32((uint32_t *)&p.latitude, 5);
484  swap_uint32((uint32_t *)&p.utc_time, 1);
485  mtk_checksum(&p.msg_class, sizeof(p)-4, &p.ck_a, &p.ck_b);
486 
487  _gps_write((uint8_t*)&p, sizeof(p), instance);
488 }
489 
490 /*
491  send a new GPS MTK 1.6 packet
492  */
493 void SITL_State::_update_gps_mtk16(const struct gps_data *d, uint8_t instance)
494 {
495  struct PACKED mtk_msg {
496  uint8_t preamble1;
497  uint8_t preamble2;
498  uint8_t size;
499  int32_t latitude;
500  int32_t longitude;
501  int32_t altitude;
502  int32_t ground_speed;
503  int32_t ground_course;
504  uint8_t satellites;
505  uint8_t fix_type;
506  uint32_t utc_date;
507  uint32_t utc_time;
508  uint16_t hdop;
509  uint8_t ck_a;
510  uint8_t ck_b;
511  } p;
512 
513  p.preamble1 = 0xd0;
514  p.preamble2 = 0xdd;
515  p.size = sizeof(p) - 5;
516  p.latitude = d->latitude * 1.0e6;
517  p.longitude = d->longitude * 1.0e6;
518  p.altitude = d->altitude * 100;
519  p.ground_speed = norm(d->speedN, d->speedE) * 100;
520  p.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 100.0f;
521  if (p.ground_course < 0.0f) {
522  p.ground_course += 360.0f * 100.0f;
523  }
524  p.satellites = d->have_lock?_sitl->gps_numsats:3;
525  p.fix_type = d->have_lock?3:1;
526 
527  // the spec is not very clear, but the time field seems to be
528  // milliseconds since the start of the day in UTC time,
529  // done in powers of 100.
530  // The date is powers of 100 as well, but in days since 1/1/2000
531  struct tm tm;
532  struct timeval tv;
533 
534  simulation_timeval(&tv);
535  tm = *gmtime(&tv.tv_sec);
536  uint32_t millisec = (tv.tv_usec / (1000*200)) * 200; // always multiple of 200
537 
538  p.utc_date = (tm.tm_year-100) + ((tm.tm_mon+1)*100) + (tm.tm_mday*100*100);
539  p.utc_time = millisec + tm.tm_sec*1000 + tm.tm_min*1000*100 + tm.tm_hour*1000*100*100;
540 
541  p.hdop = 115;
542 
543  mtk_checksum(&p.size, sizeof(p)-4, &p.ck_a, &p.ck_b);
544 
545  _gps_write((uint8_t*)&p, sizeof(p), instance);
546 }
547 
548 /*
549  send a new GPS MTK 1.9 packet
550  */
551 void SITL_State::_update_gps_mtk19(const struct gps_data *d, uint8_t instance)
552 {
553  struct PACKED mtk_msg {
554  uint8_t preamble1;
555  uint8_t preamble2;
556  uint8_t size;
557  int32_t latitude;
558  int32_t longitude;
559  int32_t altitude;
560  int32_t ground_speed;
561  int32_t ground_course;
562  uint8_t satellites;
563  uint8_t fix_type;
564  uint32_t utc_date;
565  uint32_t utc_time;
566  uint16_t hdop;
567  uint8_t ck_a;
568  uint8_t ck_b;
569  } p;
570 
571  p.preamble1 = 0xd1;
572  p.preamble2 = 0xdd;
573  p.size = sizeof(p) - 5;
574  p.latitude = d->latitude * 1.0e7;
575  p.longitude = d->longitude * 1.0e7;
576  p.altitude = d->altitude * 100;
577  p.ground_speed = norm(d->speedN, d->speedE) * 100;
578  p.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 100.0f;
579  if (p.ground_course < 0.0f) {
580  p.ground_course += 360.0f * 100.0f;
581  }
582  p.satellites = d->have_lock?_sitl->gps_numsats:3;
583  p.fix_type = d->have_lock?3:1;
584 
585  // the spec is not very clear, but the time field seems to be
586  // milliseconds since the start of the day in UTC time,
587  // done in powers of 100.
588  // The date is powers of 100 as well, but in days since 1/1/2000
589  struct tm tm;
590  struct timeval tv;
591 
592  simulation_timeval(&tv);
593  tm = *gmtime(&tv.tv_sec);
594  uint32_t millisec = (tv.tv_usec / (1000*200)) * 200; // always multiple of 200
595 
596  p.utc_date = (tm.tm_year-100) + ((tm.tm_mon+1)*100) + (tm.tm_mday*100*100);
597  p.utc_time = millisec + tm.tm_sec*1000 + tm.tm_min*1000*100 + tm.tm_hour*1000*100*100;
598 
599  p.hdop = 115;
600 
601  mtk_checksum(&p.size, sizeof(p)-4, &p.ck_a, &p.ck_b);
602 
603  _gps_write((uint8_t*)&p, sizeof(p), instance);
604 }
605 
606 /*
607  NMEA checksum
608  */
609 uint16_t SITL_State::_gps_nmea_checksum(const char *s)
610 {
611  uint16_t cs = 0;
612  const uint8_t *b = (const uint8_t *)s;
613  for (uint16_t i=1; s[i]; i++) {
614  cs ^= b[i];
615  }
616  return cs;
617 }
618 
619 /*
620  formatted print of NMEA message, with checksum appended
621  */
622 void SITL_State::_gps_nmea_printf(uint8_t instance, const char *fmt, ...)
623 {
624  char *s = nullptr;
625  uint16_t csum;
626  char trailer[6];
627 
628  va_list ap;
629 
630  va_start(ap, fmt);
631  vasprintf(&s, fmt, ap);
632  va_end(ap);
633  csum = _gps_nmea_checksum(s);
634  snprintf(trailer, sizeof(trailer), "*%02X\r\n", (unsigned)csum);
635  _gps_write((const uint8_t*)s, strlen(s), instance);
636  _gps_write((const uint8_t*)trailer, 5, instance);
637  free(s);
638 }
639 
640 
641 /*
642  send a new GPS NMEA packet
643  */
644 void SITL_State::_update_gps_nmea(const struct gps_data *d, uint8_t instance)
645 {
646  struct timeval tv;
647  struct tm *tm;
648  char tstring[20];
649  char dstring[20];
650  char lat_string[20];
651  char lng_string[20];
652 
653  simulation_timeval(&tv);
654 
655  tm = gmtime(&tv.tv_sec);
656 
657  // format time string
658  snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + tv.tv_usec*1.0e-6);
659 
660  // format date string
661  snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100);
662 
663  // format latitude
664  double deg = fabs(d->latitude);
665  snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c",
666  (unsigned)deg,
667  (deg - int(deg))*60,
668  d->latitude<0?'S':'N');
669 
670  // format longitude
671  deg = fabs(d->longitude);
672  snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c",
673  (unsigned)deg,
674  (deg - int(deg))*60,
675  d->longitude<0?'W':'E');
676 
677  _gps_nmea_printf(instance, "$GPGGA,%s,%s,%s,%01d,%02d,%04.1f,%07.2f,M,0.0,M,,",
678  tstring,
679  lat_string,
680  lng_string,
681  d->have_lock?1:0,
683  2.0,
684  d->altitude);
685  float speed_knots = norm(d->speedN, d->speedE)*1.94384449f;
686  float heading = ToDeg(atan2f(d->speedE, d->speedN));
687  if (heading < 0) {
688  heading += 360.0f;
689  }
690  _gps_nmea_printf(instance, "$GPRMC,%s,%c,%s,%s,%.2f,%.2f,%s,,",
691  tstring,
692  d->have_lock?'A':'V',
693  lat_string,
694  lng_string,
695  speed_knots,
696  heading,
697  dstring);
698 }
699 
700 void SITL_State::_sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance)
701 {
702  if (len != 0 && payload == 0) {
703  return; //SBP_NULL_ERROR;
704  }
705 
706  uint8_t preamble = 0x55;
707  _gps_write(&preamble, 1, instance);
708  _gps_write((uint8_t*)&msg_type, 2, instance);
709  _gps_write((uint8_t*)&sender_id, 2, instance);
710  _gps_write(&len, 1, instance);
711  if (len > 0) {
712  _gps_write((uint8_t*)payload, len, instance);
713  }
714 
715  uint16_t crc;
716  crc = crc16_ccitt((uint8_t*)&(msg_type), 2, 0);
717  crc = crc16_ccitt((uint8_t*)&(sender_id), 2, crc);
718  crc = crc16_ccitt(&(len), 1, crc);
719  crc = crc16_ccitt(payload, len, crc);
720  _gps_write((uint8_t*)&crc, 2, instance);
721 }
722 
723 void SITL_State::_update_gps_sbp(const struct gps_data *d, uint8_t instance)
724 {
725  struct sbp_heartbeat_t {
726  bool sys_error : 1;
727  bool io_error : 1;
728  bool nap_error : 1;
729  uint8_t res : 5;
730  uint8_t protocol_minor : 8;
731  uint8_t protocol_major : 8;
732  uint8_t res2 : 7;
733  bool ext_antenna : 1;
734  } hb; // 4 bytes
735 
736  struct PACKED sbp_gps_time_t {
737  uint16_t wn; //< GPS week number
738  uint32_t tow; //< GPS Time of Week rounded to the nearest ms
739  int32_t ns; //< Nanosecond remainder of rounded tow
740  uint8_t flags; //< Status flags (reserved)
741  } t;
742  struct PACKED sbp_pos_llh_t {
743  uint32_t tow; //< GPS Time of Week
744  double lat; //< Latitude
745  double lon; //< Longitude
746  double height; //< Height
747  uint16_t h_accuracy; //< Horizontal position accuracy estimate
748  uint16_t v_accuracy; //< Vertical position accuracy estimate
749  uint8_t n_sats; //< Number of satellites used in solution
750  uint8_t flags; //< Status flags
751  } pos;
752  struct PACKED sbp_vel_ned_t {
753  uint32_t tow; //< GPS Time of Week
754  int32_t n; //< Velocity North coordinate
755  int32_t e; //< Velocity East coordinate
756  int32_t d; //< Velocity Down coordinate
757  uint16_t h_accuracy; //< Horizontal velocity accuracy estimate
758  uint16_t v_accuracy; //< Vertical velocity accuracy estimate
759  uint8_t n_sats; //< Number of satellites used in solution
760  uint8_t flags; //< Status flags (reserved)
761  } velned;
762  struct PACKED sbp_dops_t {
763  uint32_t tow; //< GPS Time of Week
764  uint16_t gdop; //< Geometric Dilution of Precision
765  uint16_t pdop; //< Position Dilution of Precision
766  uint16_t tdop; //< Time Dilution of Precision
767  uint16_t hdop; //< Horizontal Dilution of Precision
768  uint16_t vdop; //< Vertical Dilution of Precision
769  uint8_t flags; //< Status flags (reserved)
770  } dops;
771 
772  static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
773  static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100;
774  static const uint16_t SBP_DOPS_MSGTYPE = 0x0206;
775  static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201;
776  static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205;
777  uint16_t time_week;
778  uint32_t time_week_ms;
779 
780  gps_time(&time_week, &time_week_ms);
781 
782  t.wn = time_week;
783  t.tow = time_week_ms;
784  t.ns = 0;
785  t.flags = 0;
786  _sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t, instance);
787 
788  if (!d->have_lock) {
789  return;
790  }
791 
792  pos.tow = time_week_ms;
793  pos.lon = d->longitude;
794  pos.lat= d->latitude;
795  pos.height = d->altitude;
796  pos.h_accuracy = 5e3;
797  pos.v_accuracy = 10e3;
798  pos.n_sats = _sitl->gps_numsats;
799 
800  // Send single point position solution
801  pos.flags = 0;
802  _sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos, instance);
803  // Send "pseudo-absolute" RTK position solution
804  pos.flags = 1;
805  _sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos, instance);
806 
807  velned.tow = time_week_ms;
808  velned.n = 1e3 * d->speedN;
809  velned.e = 1e3 * d->speedE;
810  velned.d = 1e3 * d->speedD;
811  velned.h_accuracy = 5e3;
812  velned.v_accuracy = 5e3;
813  velned.n_sats = _sitl->gps_numsats;
814  velned.flags = 0;
815  _sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned, instance);
816 
817  static uint32_t do_every_count = 0;
818  if (do_every_count % 5 == 0) {
819 
820  dops.tow = time_week_ms;
821  dops.gdop = 1;
822  dops.pdop = 1;
823  dops.tdop = 1;
824  dops.hdop = 100;
825  dops.vdop = 1;
826  dops.flags = 1;
827  _sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops),
828  (uint8_t*)&dops, instance);
829 
830  hb.protocol_major = 0; //Sends protocol version 0
831  _sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb),
832  (uint8_t*)&hb, instance);
833 
834  }
835  do_every_count++;
836 }
837 
838 
839 void SITL_State::_update_gps_sbp2(const struct gps_data *d, uint8_t instance)
840 {
841  struct sbp_heartbeat_t {
842  bool sys_error : 1;
843  bool io_error : 1;
844  bool nap_error : 1;
845  uint8_t res : 5;
846  uint8_t protocol_minor : 8;
847  uint8_t protocol_major : 8;
848  uint8_t res2 : 7;
849  bool ext_antenna : 1;
850  } hb; // 4 bytes
851 
852  struct PACKED sbp_gps_time_t {
853  uint16_t wn; //< GPS week number
854  uint32_t tow; //< GPS Time of Week rounded to the nearest ms
855  int32_t ns; //< Nanosecond remainder of rounded tow
856  uint8_t flags; //< Status flags (reserved)
857  } t;
858  struct PACKED sbp_pos_llh_t {
859  uint32_t tow; //< GPS Time of Week
860  double lat; //< Latitude
861  double lon; //< Longitude
862  double height; //< Height
863  uint16_t h_accuracy; //< Horizontal position accuracy estimate
864  uint16_t v_accuracy; //< Vertical position accuracy estimate
865  uint8_t n_sats; //< Number of satellites used in solution
866  uint8_t flags; //< Status flags
867  } pos;
868  struct PACKED sbp_vel_ned_t {
869  uint32_t tow; //< GPS Time of Week
870  int32_t n; //< Velocity North coordinate
871  int32_t e; //< Velocity East coordinate
872  int32_t d; //< Velocity Down coordinate
873  uint16_t h_accuracy; //< Horizontal velocity accuracy estimate
874  uint16_t v_accuracy; //< Vertical velocity accuracy estimate
875  uint8_t n_sats; //< Number of satellites used in solution
876  uint8_t flags; //< Status flags (reserved)
877  } velned;
878  struct PACKED sbp_dops_t {
879  uint32_t tow; //< GPS Time of Week
880  uint16_t gdop; //< Geometric Dilution of Precision
881  uint16_t pdop; //< Position Dilution of Precision
882  uint16_t tdop; //< Time Dilution of Precision
883  uint16_t hdop; //< Horizontal Dilution of Precision
884  uint16_t vdop; //< Vertical Dilution of Precision
885  uint8_t flags; //< Status flags (reserved)
886  } dops;
887 
888  static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF;
889  static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0102;
890  static const uint16_t SBP_DOPS_MSGTYPE = 0x0208;
891  static const uint16_t SBP_POS_LLH_MSGTYPE = 0x020A;
892  static const uint16_t SBP_VEL_NED_MSGTYPE = 0x020E;
893 
894  uint16_t time_week;
895  uint32_t time_week_ms;
896 
897  gps_time(&time_week, &time_week_ms);
898 
899  t.wn = time_week;
900  t.tow = time_week_ms;
901  t.ns = 0;
902  t.flags = 1;
903  _sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t, instance);
904 
905  if (!d->have_lock) {
906  return;
907  }
908 
909  pos.tow = time_week_ms;
910  pos.lon = d->longitude;
911  pos.lat= d->latitude;
912  pos.height = d->altitude;
913  pos.h_accuracy = 5e3;
914  pos.v_accuracy = 10e3;
915  pos.n_sats = _sitl->gps_numsats;
916 
917  // Send single point position solution
918  pos.flags = 1;
919  _sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos, instance);
920  // Send "pseudo-absolute" RTK position solution
921  pos.flags = 4;
922  _sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos, instance);
923 
924  velned.tow = time_week_ms;
925  velned.n = 1e3 * d->speedN;
926  velned.e = 1e3 * d->speedE;
927  velned.d = 1e3 * d->speedD;
928  velned.h_accuracy = 5e3;
929  velned.v_accuracy = 5e3;
930  velned.n_sats = _sitl->gps_numsats;
931  velned.flags = 1;
932  _sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned, instance);
933 
934  static uint32_t do_every_count = 0;
935  if (do_every_count % 5 == 0) {
936 
937  dops.tow = time_week_ms;
938  dops.gdop = 1;
939  dops.pdop = 1;
940  dops.tdop = 1;
941  dops.hdop = 100;
942  dops.vdop = 1;
943  dops.flags = 1;
944  _sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops),
945  (uint8_t*)&dops, instance);
946 
947  hb.protocol_major = 2; //Sends protocol version 2.0
948  _sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb),
949  (uint8_t*)&hb, instance);
950  }
951  do_every_count++;
952 }
953 
954 void SITL_State::_update_gps_nova(const struct gps_data *d, uint8_t instance)
955 {
956  static struct PACKED nova_header
957  {
958  // 0
959  uint8_t preamble[3];
960  // 3
961  uint8_t headerlength;
962  // 4
963  uint16_t messageid;
964  // 6
965  uint8_t messagetype;
966  //7
967  uint8_t portaddr;
968  //8
969  uint16_t messagelength;
970  //10
971  uint16_t sequence;
972  //12
973  uint8_t idletime;
974  //13
975  uint8_t timestatus;
976  //14
977  uint16_t week;
978  //16
979  uint32_t tow;
980  //20
981  uint32_t recvstatus;
982  // 24
983  uint16_t resv;
984  //26
985  uint16_t recvswver;
986  } header;
987 
988  struct PACKED psrdop
989  {
990  float gdop;
991  float pdop;
992  float hdop;
993  float htdop;
994  float tdop;
995  float cutoff;
996  uint32_t svcount;
997  // extra data for individual prns
998  } psrdop;
999 
1000  struct PACKED bestpos
1001  {
1002  uint32_t solstat;
1003  uint32_t postype;
1004  double lat;
1005  double lng;
1006  double hgt;
1007  float undulation;
1008  uint32_t datumid;
1009  float latsdev;
1010  float lngsdev;
1011  float hgtsdev;
1012  // 4 bytes
1013  uint8_t stnid[4];
1014  float diffage;
1015  float sol_age;
1016  uint8_t svstracked;
1017  uint8_t svsused;
1018  uint8_t svsl1;
1019  uint8_t svsmultfreq;
1020  uint8_t resv;
1021  uint8_t extsolstat;
1022  uint8_t galbeisigmask;
1023  uint8_t gpsglosigmask;
1024  } bestpos;
1025 
1026  struct PACKED bestvel
1027  {
1028  uint32_t solstat;
1029  uint32_t veltype;
1030  float latency;
1031  float age;
1032  double horspd;
1033  double trkgnd;
1034  // + up
1035  double vertspd;
1036  float resv;
1037  } bestvel;
1038 
1039  uint16_t time_week;
1040  uint32_t time_week_ms;
1041 
1042  gps_time(&time_week, &time_week_ms);
1043 
1044  header.preamble[0] = 0xaa;
1045  header.preamble[1] = 0x44;
1046  header.preamble[2] = 0x12;
1047  header.headerlength = sizeof(header);
1048  header.week = time_week;
1049  header.tow = time_week_ms;
1050 
1051  header.messageid = 174;
1052  header.messagelength = sizeof(psrdop);
1053  header.sequence += 1;
1054 
1055  psrdop.hdop = 1.20;
1056  psrdop.htdop = 1.20;
1057  _nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&psrdop, sizeof(psrdop), instance);
1058 
1059 
1060  header.messageid = 99;
1061  header.messagelength = sizeof(bestvel);
1062  header.sequence += 1;
1063 
1064  bestvel.horspd = norm(d->speedN, d->speedE);
1065  bestvel.trkgnd = ToDeg(atan2f(d->speedE, d->speedN));
1066  bestvel.vertspd = -d->speedD;
1067 
1068  _nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestvel, sizeof(bestvel), instance);
1069 
1070 
1071  header.messageid = 42;
1072  header.messagelength = sizeof(bestpos);
1073  header.sequence += 1;
1074 
1075  bestpos.lat = d->latitude;
1076  bestpos.lng = d->longitude;
1077  bestpos.hgt = d->altitude;
1078  bestpos.svsused = _sitl->gps_numsats;
1079  bestpos.latsdev=0.2;
1080  bestpos.lngsdev=0.2;
1081  bestpos.hgtsdev=0.2;
1082  bestpos.solstat=0;
1083  bestpos.postype=32;
1084 
1085  _nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestpos, sizeof(bestpos), instance);
1086 }
1087 
1088 void SITL_State::_nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance)
1089 {
1090  _gps_write(header, headerlength, instance);
1091  _gps_write(payload, payloadlen, instance);
1092 
1093  uint32_t crc = CalculateBlockCRC32(headerlength, header, (uint32_t)0);
1094  crc = CalculateBlockCRC32(payloadlen, payload, crc);
1095 
1096  _gps_write((uint8_t*)&crc, 4, instance);
1097 }
1098 
1099 #define CRC32_POLYNOMIAL 0xEDB88320L
1100 uint32_t SITL_State::CRC32Value(uint32_t icrc)
1101 {
1102  int i;
1103  uint32_t crc = icrc;
1104  for ( i = 8 ; i > 0; i-- )
1105  {
1106  if ( crc & 1 )
1107  crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL;
1108  else
1109  crc >>= 1;
1110  }
1111  return crc;
1112 }
1113 
1114 uint32_t SITL_State::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
1115 {
1116  while ( length-- != 0 )
1117  {
1118  crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff));
1119  }
1120  return( crc );
1121 }
1122 
1123 /*
1124  temporary method to use file as GPS data
1125  */
1126 void SITL_State::_update_gps_file(uint8_t instance)
1127 {
1128  static int fd = -1;
1129  static int fd2 = -1;
1130  int temp_fd;
1131  if (instance == 0) {
1132  if (fd == -1) {
1133  fd = open("/tmp/gps.dat", O_RDONLY|O_CLOEXEC);
1134  }
1135  temp_fd = fd;
1136  } else {
1137  if (fd2 == -1) {
1138  fd2 = open("/tmp/gps2.dat", O_RDONLY|O_CLOEXEC);
1139  }
1140  temp_fd = fd2;
1141  }
1142 
1143  if (temp_fd == -1) {
1144  return;
1145  }
1146  char buf[200];
1147  ssize_t ret = ::read(temp_fd, buf, sizeof(buf));
1148  if (ret > 0) {
1149  ::printf("wrote gps %u bytes\n", (unsigned)ret);
1150  _gps_write((const uint8_t *)buf, ret, instance);
1151  }
1152  if (ret == 0) {
1153  ::printf("gps rewind\n");
1154  lseek(temp_fd, 0, SEEK_SET);
1155  }
1156 }
1157 
1158 /*
1159  possibly send a new GPS packet
1160  */
1161 void SITL_State::_update_gps(double latitude, double longitude, float altitude,
1162  double speedN, double speedE, double speedD, bool have_lock)
1163 {
1164  struct gps_data d;
1165  char c;
1166 
1167  // simulate delayed lock times
1168  if (AP_HAL::millis() < _sitl->gps_lock_time*1000UL) {
1169  have_lock = false;
1170  }
1171 
1172  altitude += _sitl->gps_alt_offset;
1173 
1174  //Capture current position as basestation location for
1175  if (!_gps_has_basestation_position) {
1176  if (have_lock) {
1177  _gps_basestation_data.latitude = latitude;
1178  _gps_basestation_data.longitude = longitude;
1179  _gps_basestation_data.altitude = altitude;
1180  _gps_basestation_data.speedN = speedN;
1181  _gps_basestation_data.speedE = speedE;
1182  _gps_basestation_data.speedD = speedD;
1183  _gps_basestation_data.have_lock = have_lock;
1184  _gps_has_basestation_position = true;
1185  }
1186  }
1187 
1188  // run at configured GPS rate (default 5Hz)
1189  if ((AP_HAL::millis() - gps_state.last_update) < (uint32_t)(1000/_sitl->gps_hertz)) {
1190  return;
1191  }
1192 
1193  // swallow any config bytes
1194  if (gps_state.gps_fd != 0) {
1195  read(gps_state.gps_fd, &c, 1);
1196  }
1197  if (gps2_state.gps_fd != 0) {
1198  read(gps2_state.gps_fd, &c, 1);
1199  }
1200 
1202  gps2_state.last_update = AP_HAL::millis();
1203 
1204  d.latitude = latitude;
1205  d.longitude = longitude;
1206  // add an altitude error controlled by a slow sine wave
1207  d.altitude = altitude + _sitl->gps_noise * sinf(AP_HAL::millis() * 0.0005f);
1208 
1209  // Add offet to c.g. velocity to get velocity at antenna
1210  d.speedN = speedN;
1211  d.speedE = speedE;
1212  d.speedD = speedD;
1213  d.have_lock = have_lock;
1214 
1215  // correct the latitude, longitude, hiehgt and NED velocity for the offset between
1216  // the vehicle c.g. and GPs antenna
1217  Vector3f posRelOffsetBF = _sitl->gps_pos_offset;
1218  if (!posRelOffsetBF.is_zero()) {
1219  // get a rotation matrix following DCM conventions (body to earth)
1220  Matrix3f rotmat;
1222 
1223  // rotate the antenna offset into the earth frame
1224  Vector3f posRelOffsetEF = rotmat * posRelOffsetBF;
1225 
1226  // Add the offset to the latitude, longitude and height using a spherical earth approximation
1227  double const earth_rad_inv = 1.569612305760477e-7; // use Authalic/Volumetric radius
1228  double lng_scale_factor = earth_rad_inv / cos(radians(d.latitude));
1229  d.latitude += degrees(posRelOffsetEF.x * earth_rad_inv);
1230  d.longitude += degrees(posRelOffsetEF.y * lng_scale_factor);
1231  d.altitude -= posRelOffsetEF.z;
1232 
1233  // calculate a velocity offset due to the antenna position offset and body rotation rate
1234  // note: % operator is overloaded for cross product
1238  Vector3f velRelOffsetBF = gyro % posRelOffsetBF;
1239 
1240  // rotate the velocity offset into earth frame and add to the c.g. velocity
1241  Vector3f velRelOffsetEF = rotmat * velRelOffsetBF;
1242  d.speedN += velRelOffsetEF.x;
1243  d.speedE += velRelOffsetEF.y;
1244  d.speedD += velRelOffsetEF.z;
1245  }
1246 
1247  if (_sitl->gps_drift_alt > 0) {
1248  // slow altitude drift
1249  d.altitude += _sitl->gps_drift_alt*sinf(AP_HAL::millis()*0.001f*0.02f);
1250  }
1251 
1252  // add in some GPS lag
1253  _gps_data[next_gps_index++] = d;
1254  if (next_gps_index >= gps_delay+1) {
1255  next_gps_index = 0;
1256  }
1257 
1258  d = _gps_data[next_gps_index];
1259 
1260  if (_sitl->gps_delay != gps_delay) {
1261  // cope with updates to the delay control
1263  for (uint8_t i=0; i<gps_delay; i++) {
1264  _gps_data[i] = d;
1265  }
1266  }
1267 
1268  if (gps_state.gps_fd == 0 && gps2_state.gps_fd == 0) {
1269  return;
1270  }
1271  // Creating GPS2 data by coping GPS data
1272  gps_data d2 = d;
1273 
1274  // Applying GPS glitch
1275  // Using first gps glitch
1276  Vector3f glitch_offsets = _sitl->gps_glitch;
1277  d.latitude += glitch_offsets.x;
1278  d.longitude += glitch_offsets.y;
1279  d.altitude += glitch_offsets.z;
1280  // Using second gps glitch
1281  glitch_offsets = _sitl->gps2_glitch;
1282  d2.latitude += glitch_offsets.x;
1283  d2.longitude += glitch_offsets.y;
1284  d2.altitude += glitch_offsets.z;
1285 
1286  if (gps_state.gps_fd != 0) {
1287  _update_gps_instance((SITL::SITL::GPSType)_sitl->gps_type.get(), &d, 0);
1288  }
1289  if (gps2_state.gps_fd != 0) {
1290  _update_gps_instance((SITL::SITL::GPSType)_sitl->gps2_type.get(), &d2, 1);
1291  }
1292 }
1293 
1294 void SITL_State::_update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *data, uint8_t instance) {
1295  switch (gps_type) {
1297  // no GPS attached
1298  break;
1299 
1301  _update_gps_ubx(data, instance);
1302  break;
1303 
1305  _update_gps_mtk(data, instance);
1306  break;
1307 
1309  _update_gps_mtk16(data, instance);
1310  break;
1311 
1313  _update_gps_mtk19(data, instance);
1314  break;
1315 
1317  _update_gps_nmea(data, instance);
1318  break;
1319 
1321  _update_gps_sbp(data, instance);
1322  break;
1323 
1325  _update_gps_sbp2(data, instance);
1326  break;
1327 
1329  _update_gps_nova(data, instance);
1330  break;
1331 
1333  _update_gps_file(instance);
1334  break;
1335  }
1336 }
1337 
1338 #endif
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
int printf(const char *fmt,...)
Definition: stdio.c:113
#define GPS_LEAPSECONDS_MILLIS
Definition: AP_GPS.h:40
AP_Int8 gps_hertz
Definition: SITL.h:130
static void swap_uint32(uint32_t *v, uint8_t n)
Definition: sitl_gps.cpp:412
int vasprintf(char **strp, const char *fmt, va_list ap)
Definition: stdio.c:76
AP_Vector3f gps2_glitch
Definition: SITL.h:129
ssize_t gps_read(int fd, void *buf, size_t count)
Definition: sitl_gps.cpp:49
uint16_t _gps_nmea_checksum(const char *s)
Definition: sitl_gps.cpp:609
AP_Int8 gps2_enable
Definition: SITL.h:122
AP_Int8 gps_delay
Definition: SITL.h:123
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
Definition: sitl_gps.cpp:1114
static void mtk_checksum(const uint8_t *data, uint8_t n, uint8_t *ck_a, uint8_t *ck_b)
Definition: sitl_gps.cpp:423
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void _update_gps_file(uint8_t instance)
Definition: sitl_gps.cpp:1126
AP_Vector3f gps_glitch
Definition: SITL.h:128
#define AP_MSEC_PER_SEC
Definition: definitions.h:94
int gps_pipe(void)
Definition: sitl_gps.cpp:68
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
Quaternion quaternion
Definition: SITL.h:21
void _update_gps_nmea(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:644
AP_Int16 gps_lock_time
Definition: SITL.h:103
void _update_gps_nova(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:954
void _gps_send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size, uint8_t instance)
Definition: sitl_gps.cpp:149
static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
Definition: sitl_gps.cpp:176
void _update_gps_mtk16(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:493
void _update_gps_sbp(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:723
int gps2_pipe(void)
Definition: sitl_gps.cpp:86
static void simulation_timeval(struct timeval *tv)
Definition: sitl_gps.cpp:130
static void _set_nonblocking(int)
Definition: UARTDriver.cpp:415
int gps_fd
Definition: sitl_gps.cpp:42
double rollRate
Definition: SITL.h:19
static uint8_t next_gps_index
Definition: sitl_gps.cpp:36
#define ToDeg(x)
Definition: AP_Common.h:54
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void _gps_nmea_printf(uint8_t instance, const char *fmt,...)
Definition: sitl_gps.cpp:622
static struct gps_state gps2_state
double yawRate
Definition: SITL.h:19
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
SITL * _sitl
Definition: SIM_ADSB.cpp:28
void _update_gps_ubx(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:191
#define f(i)
const char * fmt
Definition: Printf.cpp:14
void _update_gps(double latitude, double longitude, float altitude, double speedN, double speedE, double speedD, bool have_lock)
Definition: sitl_gps.cpp:1161
AP_Vector3f gps_pos_offset
Definition: SITL.h:179
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
void _sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload, uint8_t instance)
Definition: sitl_gps.cpp:700
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
GPSType
Definition: SITL.h:58
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
AP_Float gps_byteloss
Definition: SITL.h:126
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
int client_fd
Definition: sitl_gps.cpp:42
AP_Float gps_noise
Definition: SITL.h:102
void _update_gps_mtk(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:436
#define AP_SEC_PER_WEEK
Definition: definitions.h:95
void _gps_write(const uint8_t *p, uint16_t size, uint8_t instance)
Definition: sitl_gps.cpp:104
void free(void *ptr)
Definition: malloc.c:81
void _update_gps_mtk19(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:551
uint32_t CRC32Value(uint32_t icrc)
Definition: sitl_gps.cpp:1100
double pitchRate
Definition: SITL.h:19
AP_Float gps_drift_alt
Definition: SITL.h:157
void _nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen, uint8_t instance)
Definition: sitl_gps.cpp:1088
#define CRC32_POLYNOMIAL
Definition: sitl_gps.cpp:1099
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static uint8_t gps_delay
Definition: sitl_gps.cpp:37
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
static struct gps_state gps_state
void _update_gps_sbp2(const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:839
#define PACKED
Definition: AP_Common.h:28
bool is_zero(void) const
Definition: vector3.h:159
AP_Int16 gps_alt_offset
Definition: SITL.h:104
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_Int8 gps_numsats
Definition: SITL.h:127
uint32_t last_update
Definition: sitl_gps.cpp:43
#define degrees(x)
Definition: moduletest.c:23
void _update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *d, uint8_t instance)
Definition: sitl_gps.cpp:1294
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
Definition: edc.cpp:52
struct sitl_fdm state
Definition: SITL.h:71
T x
Definition: vector3.h:67
AP_Int8 gps_type
Definition: SITL.h:124
AP_Int8 gps2_type
Definition: SITL.h:125