sitl_gps.cpp 40 KB

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