ISDisplay.cpp
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2020 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #include <stdio.h>
14 #include <iostream>
15 #include <sstream>
16 #include <iomanip>
17 #include <math.h>
18 
19 #include "ISConstants.h"
20 #include "ISUtilities.h"
21 #include "ISDisplay.h"
22 #include "ISPose.h"
23 #include "ISDataMappings.h"
24 
25 #if PLATFORM_IS_WINDOWS
26 
27 #include <conio.h>
28 
29 #endif
30 
31 #if PLATFORM_IS_LINUX || PLATFORM_IS_APPLE
32 
33 #include <unistd.h>
34 #include <sys/time.h>
35 #include <termios.h>
36 
37 #endif
38 
39 #define PRINTV3_P1 "%8.1f,%8.1f,%8.1f\n"
40 #define PRINTV3_P2 " %8.2f,%8.2f,%8.2f\n"
41 #define PRINTV3_P3 " %8.3f,%8.3f,%8.3f\n"
42 #define PRINTV4_P1 "%8.1f,%8.1f,%8.1f,%8.1f\n"
43 #define PRINTV4_P2 " %8.2f,%8.2f,%8.2f,%8.2f\n"
44 #define PRINTV4_P3 " %8.3f,%8.3f,%8.3f,%8.3f\n"
45 #define PRINTV3_LLA "%13.7f,%13.7f,%7.1f ellipsoid\n"
46 #define PRINTV3_LLA_MSL "%13.7f,%13.7f,%7.1f MSL\n"
47 #define BUF_SIZE 8192
48 
49 #define DISPLAY_DELTA_TIME 0 // show delta time instead of time
50 
52 
53 #if PLATFORM_IS_WINDOWS
54 
55 static bool ctrlHandler(DWORD fdwCtrlType)
56 {
57  switch (fdwCtrlType)
58  {
59  case CTRL_C_EVENT:
60  case CTRL_CLOSE_EVENT:
61  case CTRL_BREAK_EVENT:
62  case CTRL_LOGOFF_EVENT:
63  case CTRL_SHUTDOWN_EVENT:
64  s_controlCWasPressed = true;
65  return true;
66  default:
67  return false;
68  }
69 }
70 
71 #else
72 
73 #include <signal.h>
74 
75 static void signalFunction(int sig)
76 {
77  (void)sig;
78  s_controlCWasPressed = true;
79 }
80 
81 #endif
82 
84 {
85  cout << endl << Hello() << endl;
86 
88 
89 #if PLATFORM_IS_WINDOWS
90 
91  // Hide cursor
92  ShowCursor(false);
93 
94  if (!SetConsoleCtrlHandler((PHANDLER_ROUTINE)ctrlHandler, true))
95  {
96  std::cout << "Failed to set console ctrl handler!" << std::endl;
97  }
98 
99 #else
100 
101  signal(SIGINT, signalFunction);
102 
103 #endif
104 
105 }
106 
107 
109 {
110 
111 #if PLATFORM_IS_WINDOWS
112 
113 // m_windowsConsoleIn = GetStdHandle(STD_INPUT_HANDLE);
114  m_windowsConsoleOut = GetStdHandle(STD_OUTPUT_HANDLE);
115  CONSOLE_CURSOR_INFO cursorInfo;
116  GetConsoleCursorInfo(m_windowsConsoleOut, &cursorInfo);
117  cursorInfo.bVisible = visible;
118  SetConsoleCursorInfo(m_windowsConsoleOut, &cursorInfo);
119 
120 #endif
121 
122 }
123 
124 
126 {
127  ShowCursor(true);
128 // cout << "Shutting down..." << endl;
129 }
130 
131 
133 {
134 
135 #if PLATFORM_IS_WINDOWS
136 
137  COORD topLeft = { 0, 0 };
138  HANDLE console = GetStdHandle(STD_OUTPUT_HANDLE);
139  CONSOLE_SCREEN_BUFFER_INFO screen;
140  DWORD written;
141  GetConsoleScreenBufferInfo(console, &screen);
142  FillConsoleOutputCharacterA(console, ' ', screen.dwSize.X * screen.dwSize.Y, topLeft, &written);
143  FillConsoleOutputAttribute(console, FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE, screen.dwSize.X * screen.dwSize.Y, topLeft, &written);
144  SetConsoleCursorPosition(console, topLeft);
145 
146 #else
147 
148  printf( "\x1B[2J" ); // VT100 terminal command
149 
150 #endif
151 
152 }
153 
155 {
156 
157 #if PLATFORM_IS_WINDOWS
158 
159  COORD topLeft = { 0, 0 };
160  SetConsoleCursorPosition(m_windowsConsoleOut, topLeft);
161 
162 #else
163 
164  printf( "\x1B[H" ); // VT100 terminal command
165 
166 #endif
167 
168 }
169 
171 {
172 
173 #if PLATFORM_IS_WINDOWS
174 
175  COORD pos = { 0, (int16_t)y };
176  SetConsoleCursorPosition(m_windowsConsoleOut, pos);
177 
178 #else
179 
180  printf("\x1B[%dH", y); // VT100 terminal command
181 
182 #endif
183 
184 }
185 
187 {
188 
189 #if PLATFORM_IS_WINDOWS
190 
191  COORD pos = { (int16_t)x, (int16_t)y };
192  SetConsoleCursorPosition(m_windowsConsoleOut, pos);
193 
194 #else
195 
196  printf("\x1B[%d;%df", y, x); // VT100 terminal command
197 
198 #endif
199 
200 }
201 
203 {
204  return "$ Inertial Sense. Press CTRL-C to terminate.\n";
205 }
206 
208 {
209  return string("$ Inertial Sense. Connected. Press CTRL-C to terminate. Rx ") + std::to_string(m_rxCount) + "\n";
210 }
211 
212 string cInertialSenseDisplay::Replay(double speed)
213 {
214  char buf[BUF_SIZE];
215 
216  SNPRINTF(buf, BUF_SIZE, "$ Inertial Sense. Replay mode at %.1lfx speed. Press CTRL-C to terminate.\n", speed);
217 
218  return buf;
219 }
220 
222 {
223  return "\nThanks for using Inertial Sense!\n";
224 }
225 
227 {
228 
229 #if PLATFORM_IS_WINDOWS
230 
231 #if 0
232  // This isn't working
233  INPUT_RECORD ip;
234  DWORD numRead = 0;
235  PeekConsoleInputA(m_windowsConsoleIn, &ip, 1, &numRead);
236  if (numRead == 1)
237  {
238  ReadConsoleInputA(m_windowsConsoleIn, &ip, 1, &numRead);
239  if (numRead == 1 && ip.EventType == KEY_EVENT && ip.Event.KeyEvent.bKeyDown)
240  {
241  return ip.Event.KeyEvent.uChar.AsciiChar;
242  }
243  }
244 #else
245  if (_kbhit())
246  {
247  return _getch();
248  }
249 #endif
250 
251 #else
252 
253  struct timeval tv;
254  fd_set fds;
255  tv.tv_sec = 0;
256  tv.tv_usec = 0;
257  FD_ZERO(&fds);
258  FD_SET(STDIN_FILENO, &fds);
259  select(STDIN_FILENO + 1, &fds, NULL, NULL, &tv);
260  if (FD_ISSET(0, &fds))
261  {
262  struct termios oldt;
263  struct termios newt;
264  tcgetattr(STDIN_FILENO, &oldt); /* store old settings*/
265  newt = oldt; /* copy old settings to new settings */
266  newt.c_lflag &= ~(ICANON); /* change settings */
267  tcsetattr(STDIN_FILENO, TCSANOW, &newt); /*apply the new settings immediatly */
268  int ch = getchar(); /* standard getchar call */
269  tcsetattr(STDIN_FILENO, TCSANOW, &oldt); /* reapply the old settings */
270  return ch; /* return received char */
271  }
272 
273 #endif
274 
275  return -1;
276 }
277 
279 {
280  return s_controlCWasPressed;
281 }
282 
283 void cInertialSenseDisplay::ProcessData(p_data_t *data, bool enableReplay, double replaySpeedX)
284 {
285  if (m_displayMode == DMODE_QUIET)
286  {
287  return;
288  }
289 
290  int curTimeMs = current_weekMs();
291  m_rxCount++;
292 
293  if (enableReplay)
294  {
295  static bool isTowMode = false;
296  static int gpsTowMsOffset = 0;
297  static int msgTimeMsOffset = 0;
298  int msgTimeMs = 0;
299 
300  // Copy only new data
301  uDatasets d = {};
302  copyDataPToStructP(&d, data, sizeof(uDatasets));
303 
304  // Record message time. In either ToW or time since boot.
305  switch (data->hdr.id)
306  {
307  // Time of week - double
308  case DID_INS_1:
309  case DID_INS_2:
310  msgTimeMs = (int)(1000.0*d.ins1.timeOfWeek);
311  isTowMode = true;
312  break;
313 
314  // Time of week - uint32 ms
315  case DID_SYS_PARAMS:
316  msgTimeMs = d.gpsPos.timeOfWeekMs;
317  isTowMode = true;
318  break;
319 
320  case DID_GPS1_POS:
321  case DID_GPS1_RTK_POS:
322  msgTimeMs = d.gpsPos.timeOfWeekMs;
323  gpsTowMsOffset = (int)(1000.0*d.gpsPos.towOffset);
324  isTowMode = true;
325  break;
326 
328  msgTimeMs = d.gpsRtkRel.timeOfWeekMs;
329  isTowMode = true;
330  break;
331 
333  msgTimeMs = d.gpsPos.timeOfWeekMs;
334  gpsTowMsOffset = (int)(1000.0*d.gpsPos.towOffset);
335  isTowMode = false;
336  break;
337 
338  // Time since boot - double
339  case DID_MAGNETOMETER_1:
340  case DID_BAROMETER:
341  case DID_SYS_SENSORS:
343  case DID_DUAL_IMU:
344  case DID_INL2_STATES:
345  case DID_GPS_BASE_RAW:
346  if( isTowMode )
347  msgTimeMs = (int)(1000.0*d.imu.time) + gpsTowMsOffset;
348  else
349  msgTimeMs = (int)(1000.0*d.imu.time);
350  break;
351 
352  // Unidentified data type
353 // default: printf("Unknown DID %d\t", data->hdr.id); return;
354  }
355 
356 
357  // Control replay rate
358  if (msgTimeMs != 0 && replaySpeedX>0.0)
359  {
360  for (;;)
361  {
362  curTimeMs = current_weekMs();
363 
364  // Replay speed
365  int replayTimeMs = (int)(long)(((double)curTimeMs)*replaySpeedX);
366 
367  // Reinitialize message offset
368  if (abs(msgTimeMs + msgTimeMsOffset - replayTimeMs) > 1500)
369  msgTimeMsOffset = replayTimeMs - msgTimeMs;
370 
371  // Proceed if we're caught up
372  if (replayTimeMs >= msgTimeMs + msgTimeMsOffset)
373  break;
374 
375  // Add delay
376 // SLEEP_US(1000);
377  SLEEP_MS(10);
378  }
379  }
380  }
381 
382 
383  static int timeSinceRefreshMs = 0;
384  static int timeSinceClearMs = 0;
385  static char idHist[DID_COUNT] = { 0 };
387  {
388  // Clear display every 2 seconds or if we start seeing new messages.
389  if (curTimeMs - timeSinceClearMs > 2000 || curTimeMs < timeSinceClearMs || idHist[data->hdr.id] == 0)
390  {
391  Clear();
392  idHist[data->hdr.id] = 1;
393  timeSinceClearMs = curTimeMs;
394  }
395  }
396 
397 
398  // Display Data
399  switch (m_displayMode)
400  {
401  default:
403  // fall through
404  case DMODE_PRETTY:
405 
406  // Data stays at fixed location (no scroll history)
407  DataToVector(data);
408 
409  // Limit printData display updates to 20Hz (50 ms)
410  if (curTimeMs - timeSinceRefreshMs > 50 || curTimeMs < timeSinceRefreshMs)
411  {
412  Home();
413  if (enableReplay)
414  cout << Replay(replaySpeedX) << endl;
415  else
416  cout << Connected() << endl;
417 
418  cout << VectortoString();
419 
420  timeSinceRefreshMs = curTimeMs;
421  }
422  break;
423 
424  case DMODE_STATS:
425  // Limit printData display updates to 20Hz (50 ms)
426  if (curTimeMs - timeSinceRefreshMs > 50 || curTimeMs < timeSinceRefreshMs)
427  {
428  Home();
429  cout << Connected() << endl;
430  DataToStats(data);
431 
432  timeSinceRefreshMs = curTimeMs;
433  }
434  break;
435 
436 
437  case DMODE_SCROLL: // Scroll display
438  cout << DataToString(data) << endl;
439  break;
440  }
441 
442 
443 
444 }
445 
447 {
448  stringstream ss;
449 
450  for (size_t i = 0; i < m_didMsgs.size(); i++)
451  {
452  if (m_didMsgs[i].size())
453  {
454  ss << m_didMsgs[i];
455  }
456  }
457 
458  return ss.str();
459 }
460 
462 {
463  size_t id = data->hdr.id;
464  if (m_didMsgs.size() <= id)
465  { // Resize vector if necessary
466  m_didMsgs.resize(id + 1);
467  }
468  // Add string to vector
469  m_didMsgs[id] = DataToString(data);
470 }
471 
473 {
474  size_t id = data->hdr.id;
475  if (m_didStats.size() <= id)
476  { // Resize vector if necessary
477  m_didStats.resize(id + 1);
478  }
479 
480  // Update stats
481  int curTimeMs = current_weekMs();
482  sDidStats &s = m_didStats[id];
483  s.count++;
484  if(s.lastTimeMs)
485  s.dtMs = curTimeMs - s.lastTimeMs;
486  s.lastTimeMs = curTimeMs;
487 
488  // Display stats
489  printf(" Name DID Count dt\n");
490  for (int i = 0; i < (int)m_didStats.size(); i++)
491  {
492  s = m_didStats[i];
493  if (s.count)
494  {
495  printf("%20s %4d %9d %9.3lf\n", cISDataMappings::GetDataSetName(i), i, s.count, s.dtMs*0.001);
496  }
497  }
498 }
499 
501 {
502  uDatasets d = {};
503 
504  // Copy only new data
505  copyDataPToStructP(&d, data, sizeof(uDatasets));
506 
507  string str;
508  switch (data->hdr.id)
509  {
510  case DID_DEV_INFO: str = DataToStringDevInfo(d.devInfo, data->hdr); break;
511  case DID_DUAL_IMU: str = DataToStringDualIMU(d.dualImu, data->hdr); break;
512  case DID_PREINTEGRATED_IMU: str = DataToStringPreintegratedImu(d.pImu, data->hdr); break;
513  case DID_INS_1: str = DataToStringINS1(d.ins1, data->hdr); break;
514  case DID_INS_2: str = DataToStringINS2(d.ins2, data->hdr); break;
515  case DID_INS_3: str = DataToStringINS3(d.ins3, data->hdr); break;
516  case DID_INS_4: str = DataToStringINS4(d.ins4, data->hdr); break;
517  case DID_MAGNETOMETER_1:
518  case DID_MAGNETOMETER_2: str = DataToStringMag(d.mag, data->hdr); break;
519  case DID_MAG_CAL: str = DataToStringMagCal(d.magCal, data->hdr); break;
520  case DID_BAROMETER: str = DataToStringBaro(d.baro, data->hdr); break;
521  case DID_GPS1_POS: str = DataToStringGpsPos(d.gpsPos, data->hdr, "DID_GPS1_POS"); break;
522  case DID_GPS2_POS: str = DataToStringGpsPos(d.gpsPos, data->hdr, "DID_GPS2_POS"); break;
523  case DID_GPS1_RTK_POS: str = DataToStringGpsPos(d.gpsPos, data->hdr, "DID_GPS1_RTK_POS"); break;
524  case DID_GPS1_RTK_POS_REL: str = DataToStringRtkRel(d.gpsRtkRel, data->hdr, "DID_GPS1_RTK_POS_REL"); break;
525  case DID_GPS1_RTK_POS_MISC: str = DataToStringRtkMisc(d.gpsRtkMisc, data->hdr, "RTK_POS_MISC"); break;
526  case DID_GPS2_RTK_CMP_REL: str = DataToStringRtkRel(d.gpsRtkRel, data->hdr, "DID_GPS2_RTK_CMP_REL"); break;
527  case DID_GPS2_RTK_CMP_MISC: str = DataToStringRtkMisc(d.gpsRtkMisc, data->hdr, "RTK_CMP_MISC"); break;
528  case DID_GPS1_RAW:
529  case DID_GPS2_RAW:
530  case DID_GPS_BASE_RAW: str = DataToStringRawGPS(d.gpsRaw, data->hdr); break;
531  case DID_SURVEY_IN: str = DataToStringSurveyIn(d.surveyIn, data->hdr); break;
532  case DID_SYS_PARAMS: str = DataToStringSysParams(d.sysParams, data->hdr); break;
533  case DID_SYS_SENSORS: str = DataToStringSysSensors(d.sysSensors, data->hdr); break;
534  case DID_RTOS_INFO: str = DataToStringRTOS(d.rtosInfo, data->hdr); break;
535  case DID_SENSORS_ADC: str = DataToStringSensorsADC(d.sensorsAdc, data->hdr); break;
536  default:
537 #if 0 // List all DIDs
538  char buf[128];
539  SNPRINTF(buf, 128, "DID: %d\n", data->hdr.id);
540  str = buf;
541 #endif
542  break;
543  }
544 
545  return str;
546 }
547 
548 char* cInertialSenseDisplay::StatusToString(char* ptr, char* ptrEnd, const uint32_t insStatus, const uint32_t hdwStatus)
549 {
550  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tSTATUS\n");
551  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t\tSatellite Rx %d Aiding: Mag %d, GPS (Hdg %d, Pos %d)\n",
552  (hdwStatus & HDW_STATUS_GPS_SATELLITE_RX) != 0,
553  (insStatus & INS_STATUS_MAG_AIDING_HEADING) != 0,
554  (insStatus & INS_STATUS_GPS_AIDING_HEADING) != 0,
555  (insStatus & INS_STATUS_GPS_AIDING_POS_VEL) != 0);
556  if (insStatus & INS_STATUS_NAV_MODE)
557  {
558  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t\tMode: NAV ");
559  }
560  else
561  {
562  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t\tMode: AHRS");
563  }
564  switch (INS_STATUS_SOLUTION(insStatus))
565  {
566  default:
567  case INS_STATUS_SOLUTION_OFF: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: OFF\n"); break;
568  case INS_STATUS_SOLUTION_ALIGNING: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: ALIGNING\n"); break;
569  case INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: ALIGNMENT COMPLETE\n"); break;
570  case INS_STATUS_SOLUTION_NAV: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: NAV\n"); break;
571  case INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: NAV HIGH VARIANCE\n"); break;
572  case INS_STATUS_SOLUTION_AHRS: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: AHRS\n"); break;
573  case INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE: ptr += SNPRINTF(ptr, ptrEnd - ptr, " Solution: AHRS HIGH VARIANCE\n"); break;
574  }
575 // ptr += SNPRINTF(ptr, ptrEnd - ptr, " Align Good: Att %d, Vel %d, Pos %d\n",
576 // (insStatus & INS_STATUS_ATT_ALIGN_GOOD) != 0,
577 // (insStatus & INS_STATUS_VEL_ALIGN_GOOD) != 0,
578 // (insStatus & INS_STATUS_POS_ALIGN_GOOD) != 0);
579  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t\tErrors Rx parse %d, temperature %d, self-test %d\n",
581  (hdwStatus & HDW_STATUS_ERR_TEMPERATURE) != 0,
582  (hdwStatus & HDW_STATUS_BIT_FAULT) != 0);
583 
584  return ptr;
585 }
586 
587 char* cInertialSenseDisplay::InsStatusToSolStatusString(char* ptr, char* ptrEnd, const uint32_t insStatus)
588 {
589  switch (INS_STATUS_SOLUTION(insStatus))
590  {
591  default:
592  case INS_STATUS_SOLUTION_OFF: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", OFF "); break;
593  case INS_STATUS_SOLUTION_ALIGNING: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", ALIGNING "); break;
594  case INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", COMPLETE "); break;
595  case INS_STATUS_SOLUTION_NAV: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", NAV "); break;
596  case INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", NAV VARIA"); break;
597  case INS_STATUS_SOLUTION_AHRS: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", AHRS "); break;
598  case INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE: ptr += SNPRINTF(ptr, ptrEnd - ptr, ", AHRS VARI"); break;
599  }
600 
601  return ptr;
602 }
603 
605 {
606  (void)hdr;
607  char buf[BUF_SIZE];
608  char* ptr = buf;
609  char* ptrEnd = buf + BUF_SIZE;
610  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_INS_1:");
611 
612 #if DISPLAY_DELTA_TIME==1
613  static double lastTime = 0;
614  double dtMs = 1000.0*(ins1.timeOfWeek - lastTime);
615  lastTime = ins1.timeOfWeek;
616  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
617 #else
618  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", ins1.timeOfWeek);
619 #endif
620 
622  { // Single line format
623  ptr = InsStatusToSolStatusString(ptr, ptrEnd, ins1.insStatus);
624  ptr += SNPRINTF(ptr, ptrEnd - ptr, " theta[%6.2f,%6.2f,%7.2f], uvw[%6.2f,%6.2f,%6.2f], lla[%12.7f,%12.7f,%7.1f], ned[%6.3f,%6.3f,%6.3f]",
625  ins1.theta[0] * C_RAD2DEG_F,
626  ins1.theta[1] * C_RAD2DEG_F,
627  ins1.theta[2] * C_RAD2DEG_F,
628  ins1.uvw[0], ins1.uvw[1], ins1.uvw[2],
629  ins1.lla[0], ins1.lla[1], ins1.lla[2],
630  ins1.ned[0], ins1.ned[1], ins1.ned[2]);
631  }
632  else
633  { // Spacious format
634  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tEuler\t");
635  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P2,
636  ins1.theta[0] * C_RAD2DEG_F, // Roll
637  ins1.theta[1] * C_RAD2DEG_F, // Pitch
638  ins1.theta[2] * C_RAD2DEG_F); // Yaw
639  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tUWV\t");
640  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P1,
641  ins1.uvw[0], // U body velocity
642  ins1.uvw[1], // V body velocity
643  ins1.uvw[2]); // W body velocity
644  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tLLA\t");
645  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_LLA,
646  ins1.lla[0], // INS Latitude
647  ins1.lla[1], // INS Longitude
648  ins1.lla[2]); // INS Ellipsoid altitude (meters)
649  ptr = StatusToString(ptr, ptrEnd, ins1.insStatus, ins1.hdwStatus);
650  }
651 
652  return buf;
653 }
654 
656 {
657  (void)hdr;
658  char buf[BUF_SIZE];
659  char* ptr = buf;
660  char* ptrEnd = buf + BUF_SIZE;
661  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_INS_2:");
662 
663 #if DISPLAY_DELTA_TIME==1
664  static double lastTime = 0;
665  double dtMs = 1000.0*(ins2.timeOfWeek - lastTime);
666  lastTime = ins2.timeOfWeek;
667  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
668 #else
669  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", ins2.timeOfWeek);
670 #endif
671 
673  { // Single line format
674  ptr = InsStatusToSolStatusString(ptr, ptrEnd, ins2.insStatus);
675  ptr += SNPRINTF(ptr, ptrEnd - ptr, " qn2b[%6.3f,%6.3f,%6.3f,%6.3f], uvw[%6.2f,%6.2f,%6.2f], lla[%12.7f,%12.7f,%7.1f]",
676  ins2.qn2b[0], ins2.qn2b[1], ins2.qn2b[2], ins2.qn2b[3],
677  ins2.uvw[0], ins2.uvw[1], ins2.uvw[2],
678  ins2.lla[0], ins2.lla[1], ins2.lla[2]);
679  }
680  else
681  { // Spacious format
682  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tQn2b\t");
683  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV4_P3, // Quaternion attitude rotation
684  ins2.qn2b[0], // W
685  ins2.qn2b[1], // X
686  ins2.qn2b[2], // Y
687  ins2.qn2b[3]); // Z
688  float theta[3];
689  quat2euler(ins2.qn2b, theta);
690  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t(Euler)\t");
691  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P2, // Convert quaternion to euler rotation
692  theta[0] * C_RAD2DEG_F, // Roll
693  theta[1] * C_RAD2DEG_F, // Pitch
694  theta[2] * C_RAD2DEG_F); // Yaw
695  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tUWV\t");
696  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P1,
697  ins2.uvw[0], // U body velocity
698  ins2.uvw[1], // V body velocity
699  ins2.uvw[2]); // W body velocity
700  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tLLA\t");
701  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_LLA,
702  ins2.lla[0], // INS Latitude
703  ins2.lla[1], // INS Longitude
704  ins2.lla[2]); // INS Ellipsoid altitude (meters)
705  ptr = StatusToString(ptr, ptrEnd, ins2.insStatus, ins2.hdwStatus);
706  }
707 
708  return buf;
709 }
710 
712 {
713  (void)hdr;
714  char buf[BUF_SIZE];
715  char* ptr = buf;
716  char* ptrEnd = buf + BUF_SIZE;
717  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_INS_3:");
718 
719 #if DISPLAY_DELTA_TIME==1
720  static double lastTime = 0;
721  double dtMs = 1000.0*(ins3.timeOfWeek - lastTime);
722  lastTime = ins3.timeOfWeek;
723  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
724 #else
725  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", ins3.timeOfWeek);
726 #endif
727 
729  { // Single line format
730  ptr = InsStatusToSolStatusString(ptr, ptrEnd, ins3.insStatus);
731  ptr += SNPRINTF(ptr, ptrEnd - ptr, " qn2b[%6.3f,%6.3f,%6.3f,%6.3f], uvw[%6.2f,%6.2f,%6.2f], lla[%12.7f,%12.7f,%7.1f]",
732  ins3.qn2b[0], ins3.qn2b[1], ins3.qn2b[2], ins3.qn2b[3],
733  ins3.uvw[0], ins3.uvw[1], ins3.uvw[2],
734  ins3.lla[0], ins3.lla[1], ins3.lla[2]);
735  }
736  else
737  { // Spacious format
738  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tQn2b\t");
739  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV4_P3, // Quaternion attitude rotation
740  ins3.qn2b[0], // W
741  ins3.qn2b[1], // X
742  ins3.qn2b[2], // Y
743  ins3.qn2b[3]); // Z
744  float theta[3];
745  quat2euler(ins3.qn2b, theta);
746  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t(Euler)\t");
747  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P2, // Convert quaternion to euler rotation
748  theta[0] * C_RAD2DEG_F, // Roll
749  theta[1] * C_RAD2DEG_F, // Pitch
750  theta[2] * C_RAD2DEG_F); // Yaw
751  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tUWV\t");
752  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P1,
753  ins3.uvw[0], // U body velocity
754  ins3.uvw[1], // V body velocity
755  ins3.uvw[2]); // W body velocity
756  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tLLA\t");
757  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_LLA_MSL,
758  ins3.lla[0], // INS Latitude
759  ins3.lla[1], // INS Longitude
760  ins3.lla[2]); // INS Ellipsoid altitude (meters)
761  ptr = StatusToString(ptr, ptrEnd, ins3.insStatus, ins3.hdwStatus);
762  }
763 
764  return buf;
765 }
766 
768 {
769  (void)hdr;
770  char buf[BUF_SIZE];
771  char* ptr = buf;
772  char* ptrEnd = buf + BUF_SIZE;
773  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_INS_4:");
774 
775 #if DISPLAY_DELTA_TIME==1
776  static double lastTime = 0;
777  double dtMs = 1000.0*(ins4.timeOfWeek - lastTime);
778  lastTime = ins4.timeOfWeek;
779  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
780 #else
781  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", ins4.timeOfWeek);
782 #endif
783 
785  { // Single line format
786  ptr = InsStatusToSolStatusString(ptr, ptrEnd, ins4.insStatus);
787  ptr += SNPRINTF(ptr, ptrEnd - ptr, " qe2b[%6.3f,%6.3f,%6.3f,%6.3f], ve[%6.2f,%6.2f,%6.2f], ecef[%12.7f,%12.7f,%7.1f]",
788  ins4.qe2b[0], ins4.qe2b[1], ins4.qe2b[2], ins4.qe2b[3],
789  ins4.ve[0], ins4.ve[1], ins4.ve[2],
790  ins4.ecef[0], ins4.ecef[1], ins4.ecef[2]);
791  }
792  else
793  { // Spacious format
794  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tQe2b\t");
795  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV4_P3, // Quaternion attitude rotation
796  ins4.qe2b[0], // W
797  ins4.qe2b[1], // X
798  ins4.qe2b[2], // Y
799  ins4.qe2b[3]); // Z
800  float theta[3];
801  qe2b2EulerNedEcef(theta, (float*)ins4.qe2b, (double*)ins4.ecef);
802  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\t(Euler)\t");
803  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P2, // Convert quaternion to euler rotation
804  theta[0] * C_RAD2DEG_F, // Roll
805  theta[1] * C_RAD2DEG_F, // Pitch
806  theta[2] * C_RAD2DEG_F); // Yaw
807  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tVE\t");
808  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
809  ins4.ve[0], // X ECEF velocity
810  ins4.ve[1], // Y ECEF velocity
811  ins4.ve[2]); // Z ECEF velocity
812  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tECEF\t");
813  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
814  ins4.ecef[0], // X ECEF position
815  ins4.ecef[1], // Y ECEF position
816  ins4.ecef[2]); // Z ECEF position
817  ptr = StatusToString(ptr, ptrEnd, ins4.insStatus, ins4.hdwStatus);
818  }
819 
820  return buf;
821 }
822 
824 {
825  (void)hdr;
826  char buf[BUF_SIZE];
827  char* ptr = buf;
828  char* ptrEnd = buf + BUF_SIZE;
829  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_DUAL_IMU:");
830 
831 #if DISPLAY_DELTA_TIME==1
832  static double lastTime = 0;
833  double dtMs = 1000.0*(imu.time - lastTime);
834  lastTime = imu.time;
835  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
836 #else
837  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", imu.time);
838 #endif
839 
841  { // Single line format
842  for (int i = 0; i < 2; i++)
843  {
844  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", pqr[%5.1f,%5.1f,%5.1f]",
845  imu.I[i].pqr[0] * C_RAD2DEG_F,
846  imu.I[i].pqr[1] * C_RAD2DEG_F,
847  imu.I[i].pqr[2] * C_RAD2DEG_F);
848  }
849  for (int i = 0; i < 2; i++)
850  {
851  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", acc[%5.1f,%5.1f,%5.1f]",
852  imu.I[i].acc[0], imu.I[i].acc[1], imu.I[i].acc[2]);
853  }
854  }
855  else
856  { // Spacious format
857  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
858  for (int i = 0; i < 2; i++)
859  {
860  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tPQR\t");
861  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P1,
862  imu.I[i].pqr[0] * C_RAD2DEG_F, // P angular rate
863  imu.I[i].pqr[1] * C_RAD2DEG_F, // Q angular rate
864  imu.I[i].pqr[2] * C_RAD2DEG_F); // R angular rate
865  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tAcc\t");
866  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P1,
867  imu.I[i].acc[0], // X acceleration
868  imu.I[i].acc[1], // Y acceleration
869  imu.I[i].acc[2]); // Z acceleration
870  }
871  }
872 
873  return buf;
874 }
875 
877 {
878  (void)hdr;
879  char buf[BUF_SIZE];
880  char* ptr = buf;
881  char* ptrEnd = buf + BUF_SIZE;
882  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_PREINTEGRATED_IMU:");
883 
884 #if DISPLAY_DELTA_TIME==1
885  static double lastTime = 0;
886  double dtMs = 1000.0*(imu.time - lastTime);
887  lastTime = imu.time;
888  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
889 #else
890  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs, dt:%6.3f", imu.time, imu.dt);
891 #endif
892 
894  { // Single line format
895  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", theta1[%6.3f,%6.3f,%6.3f], vel1[%6.3f,%6.3f,%6.3f]",
896  imu.theta1[0] * C_RAD2DEG_F,
897  imu.theta1[1] * C_RAD2DEG_F,
898  imu.theta1[2] * C_RAD2DEG_F,
899  imu.vel1[0], imu.vel1[1], imu.vel1[2]);
900  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", theta2[%6.3f,%6.3f,%6.3f], vel2[%6.3f,%6.3f,%6.3f]",
901  imu.theta2[0] * C_RAD2DEG_F,
902  imu.theta2[1] * C_RAD2DEG_F,
903  imu.theta2[2] * C_RAD2DEG_F,
904  imu.vel2[0], imu.vel2[1], imu.vel2[2]);
905  }
906  else
907  { // Spacious format
908  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tIMU1 theta1\t");
909  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
910  imu.theta1[0] * C_RAD2DEG_F, // IMU1 P angular rate
911  imu.theta1[1] * C_RAD2DEG_F, // IMU1 Q angular rate
912  imu.theta1[2] * C_RAD2DEG_F); // IMU1 R angular rate
913  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tIMU2 theta2\t");
914  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
915  imu.theta2[0] * C_RAD2DEG_F, // IMU2 P angular rate
916  imu.theta2[1] * C_RAD2DEG_F, // IMU2 Q angular rate
917  imu.theta2[2] * C_RAD2DEG_F); // IMU2 R angular rate
918  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tIMU1 vel1\t");
919  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
920  imu.vel1[0], // IMU1 X acceleration
921  imu.vel1[1], // IMU1 Y acceleration
922  imu.vel1[2]); // IMU1 Z acceleration
923  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tIMU2 vel2\t");
924  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
925  imu.vel2[0], // IMU2 X acceleration
926  imu.vel2[1], // IMU2 Y acceleration
927  imu.vel2[2]); // IMU2 Z acceleration
928  }
929 
930  return buf;
931 }
932 
934 {
935  (void)hdr;
936  char buf[BUF_SIZE];
937  char* ptr = buf;
938  char* ptrEnd = buf + BUF_SIZE;
939  int i = 0;
940  if (hdr.id == DID_MAGNETOMETER_2) i = 1;
941  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_MAGNETOMETER_%d:", i + 1);
942 
943 #if DISPLAY_DELTA_TIME==1
944  static double lastTime[2] = { 0 };
945  double dtMs = 1000.0*(mag.time - lastTime[i]);
946  lastTime[i] = mag.time;
947  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
948 #else
949  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", mag.time);
950 #endif
951 
953  { // Single line format
954  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", mag[%6.2f,%6.2f,%6.2f]",
955  mag.mag[0], // X magnetometer
956  mag.mag[1], // Y magnetometer
957  mag.mag[2]); // Z magnetometer
958  }
959  else
960  { // Spacious format
961  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tmag\t");
962  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P2,
963  mag.mag[0], // X magnetometer
964  mag.mag[1], // Y magnetometer
965  mag.mag[2]); // Z magnetometer
966  }
967 
968  return buf;
969 }
970 
972 {
973  (void)hdr;
974  char buf[BUF_SIZE];
975  char* ptr = buf;
976  char* ptrEnd = buf + BUF_SIZE;
977  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_MAG_CAL:");
978 
979  switch (mag.recalCmd)
980  {
981  default: ptr += SNPRINTF(ptr, ptrEnd - ptr, " recalCmd %3d, ", mag.recalCmd); break;
982  case MAG_RECAL_CMD_MULTI_AXIS: ptr += SNPRINTF(ptr, ptrEnd - ptr, " recalCmd %3d (MULTI-AXIS ), ", mag.recalCmd); break;
983  case MAG_RECAL_CMD_SINGLE_AXIS: ptr += SNPRINTF(ptr, ptrEnd - ptr, " recalCmd %3d (SINGLE-AXIS), ", mag.recalCmd); break;
984  case MAG_RECAL_CMD_ABORT: ptr += SNPRINTF(ptr, ptrEnd - ptr, " recalCmd %3d (ABORT ), ", mag.recalCmd); break;
985  }
986 
987  { // Single line format
988  ptr += SNPRINTF(ptr, ptrEnd - ptr, " progress: %3.0f %%, declination: %4.1f",
989  mag.progress,
990  mag.declination * C_RAD2DEG_F);
991  }
992 
994  {
995  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
996  }
997 
998  return buf;
999 }
1000 
1002 {
1003  (void)hdr;
1004  char buf[BUF_SIZE];
1005  char* ptr = buf;
1006  char* ptrEnd = buf + BUF_SIZE;
1007  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_BAROMETER:");
1008 
1009 #if DISPLAY_DELTA_TIME==1
1010  static double lastTime = 0;
1011  double dtMs = 1000.0*(baro.time - lastTime);
1012  lastTime = baro.time;
1013  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
1014 #else
1015  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", baro.time);
1016 #endif
1017 
1018  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", %.2fkPa", baro.bar);
1019  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", %.1fm", baro.mslBar);
1020  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", %.2fC", baro.barTemp);
1021  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", Humid. %.1f%%", baro.humidity);
1022 
1023  if (m_displayMode == DMODE_PRETTY)
1024  {
1025  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
1026  }
1027 
1028  return buf;
1029 }
1030 
1031 string cInertialSenseDisplay::DataToStringGpsPos(const gps_pos_t &gps, const p_data_hdr_t& hdr, const string didName)
1032 {
1033  (void)hdr;
1034  char buf[BUF_SIZE];
1035  char* ptr = buf;
1036  char* ptrEnd = buf + BUF_SIZE;
1037 
1038  ptr += SNPRINTF(ptr, ptrEnd - ptr, "%s:", didName.c_str());
1039 
1040 #if DISPLAY_DELTA_TIME==1
1041  static int lastTimeMs = 0;
1042  int dtMs = gps.timeOfWeekMs - lastTimeMs;
1043  lastTimeMs = gps.timeOfWeekMs;
1044  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %3dms", dtMs);
1045 #else
1046  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %dms", gps.timeOfWeekMs);
1047 #endif
1048 
1049  if (m_displayMode == DMODE_SCROLL)
1050  { // Single line format
1051  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", LLA[%12.7f,%12.7f,%7.1f], %d sats, %4.1f cno, %4.3f hAcc, %4.3f vAcc, %4.3f pDop",
1052  gps.lla[0], gps.lla[1], gps.lla[2],
1054  gps.hAcc, gps.vAcc, gps.pDop);
1055  }
1056  else
1057  { // Spacious format
1058  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\tSats: %2d, ",
1059  gps.status&GPS_STATUS_NUM_SATS_USED_MASK); // Satellites used in solution
1060  ptr += SNPRINTF(ptr, ptrEnd - ptr, "Status: 0x%08x (", gps.status);
1061  switch (gps.status&GPS_STATUS_FIX_MASK)
1062  {
1063  default:
1064  case GPS_STATUS_FIX_NONE: ptr += SNPRINTF(ptr, ptrEnd - ptr, "%d", (gps.status&GPS_STATUS_FIX_MASK)>>GPS_STATUS_FIX_BIT_OFFSET); break;
1065  case GPS_STATUS_FIX_2D: ptr += SNPRINTF(ptr, ptrEnd - ptr, "2D"); break;
1066  case GPS_STATUS_FIX_3D: ptr += SNPRINTF(ptr, ptrEnd - ptr, "3D"); break;
1067  case GPS_STATUS_FIX_RTK_SINGLE: ptr += SNPRINTF(ptr, ptrEnd - ptr, "RTK Single"); break;
1068  case GPS_STATUS_FIX_RTK_FLOAT: ptr += SNPRINTF(ptr, ptrEnd - ptr, "RTK Float"); break;
1069  case GPS_STATUS_FIX_RTK_FIX: ptr += SNPRINTF(ptr, ptrEnd - ptr, "RTK FIX"); break;
1070  }
1071  ptr += SNPRINTF(ptr, ptrEnd - ptr, "),\thAcc: %.3f m cno: %3.1f dBHz\n", gps.hAcc, gps.cnoMean); // Position accuracy
1072  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tLLA: ");
1073  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_LLA,
1074  gps.lla[0], // GPS Latitude
1075  gps.lla[1], // GPS Longitude
1076  gps.lla[2]); // GPS Ellipsoid altitude (meters)
1078  {
1080  {
1081  ptr += SNPRINTF(ptr, ptrEnd - ptr, "Compassing, ");
1082  }
1083  if (gps.status&GPS_STATUS_FLAGS_RTK_RAW_GPS_DATA_ERROR) { ptr += SNPRINTF(ptr, ptrEnd - ptr, "Raw error, "); }
1084  switch (gps.status&GPS_STATUS_FLAGS_ERROR_MASK)
1085  {
1086  case GPS_STATUS_FLAGS_RTK_BASE_DATA_MISSING: ptr += SNPRINTF(ptr, ptrEnd - ptr, "Base missing, "); break;
1087  case GPS_STATUS_FLAGS_RTK_BASE_POSITION_MOVING: ptr += SNPRINTF(ptr, ptrEnd - ptr, "Moving base, "); break;
1088  case GPS_STATUS_FLAGS_RTK_BASE_POSITION_INVALID: ptr += SNPRINTF(ptr, ptrEnd - ptr, "Moving invalid, "); break;
1089  }
1090  }
1091  }
1092 
1093  return buf;
1094 }
1095 
1096 string cInertialSenseDisplay::DataToStringRtkRel(const gps_rtk_rel_t &rel, const p_data_hdr_t& hdr, const string didName)
1097 {
1098  (void)hdr;
1099  char buf[BUF_SIZE];
1100  char* ptr = buf;
1101  char* ptrEnd = buf + BUF_SIZE;
1102 
1103  ptr += SNPRINTF(ptr, ptrEnd - ptr, "%s:", didName.c_str());
1104 
1105 #if DISPLAY_DELTA_TIME==1
1106  static int lastTimeMs = 0;
1107  int dtMs = rel.timeOfWeekMs - lastTimeMs;
1108  lastTimeMs = rel.timeOfWeekMs;
1109  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %3dms", dtMs);
1110 #else
1111  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %dms", rel.timeOfWeekMs);
1112 #endif
1113 
1114  if (m_displayMode == DMODE_SCROLL)
1115  { // Single line format
1116  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", V2B[%10.3f,%10.3f,%9.2f], %4.1f age, %4.1f arRatio, %4.3f dist, %4.2f bear",
1117  rel.baseToRoverVector[0], rel.baseToRoverVector[1], rel.baseToRoverVector[2],
1119  }
1120  else
1121  { // Spacious format
1122  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tvectorToRover: ");
1123  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_P3,
1124  rel.baseToRoverVector[0], // Vector to base in ECEF
1125  rel.baseToRoverVector[1], // Vector to base in ECEF
1126  rel.baseToRoverVector[2]); // Vector to base in ECEF
1127  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tRTK:\tdiffAge:%5.1fs arRatio: %4.1f dist:%7.2fm bear:%6.1f\n",
1129  }
1130 
1131  return buf;
1132 }
1133 
1134 string cInertialSenseDisplay::DataToStringRtkMisc(const gps_rtk_misc_t& rtk, const p_data_hdr_t& hdr, const string didName)
1135 {
1136  (void)hdr;
1137  char buf[BUF_SIZE];
1138  char* ptr = buf;
1139  char* ptrEnd = buf + BUF_SIZE;
1140  const char* terminator = (m_displayMode != DMODE_SCROLL ? "\n" : "");
1141  ptr += SNPRINTF(buf, ptrEnd - ptr, "%s: T=%d, lla[%4.7f,%4.7f,%7.3f], A[%3.3f,%3.3f,%3.3f], AR:%3.3f, dop(g,h,v)[%3.3f,%3.3f,%3.3f] %s",
1142  didName.c_str(),
1143  rtk.timeOfWeekMs, rtk.baseLla[0], rtk.baseLla[1], rtk.baseLla[2],
1144  rtk.accuracyPos[0], rtk.accuracyPos[1], rtk.accuracyPos[2],
1145  rtk.arThreshold,
1146  rtk.gDop, rtk.hDop, rtk.vDop,
1147  terminator);
1148 
1149  if (m_displayMode != DMODE_SCROLL)
1150  {
1151  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
1152  }
1153 
1154  return buf;
1155 }
1156 
1158 {
1159  (void)hdr;
1160  char buf[BUF_SIZE];
1161  char* ptr = buf;
1162  char* ptrEnd = buf + BUF_SIZE;
1163  const char* terminator = (m_displayMode != DMODE_SCROLL ? "\n" : "");
1164  ptr += SNPRINTF(buf, ptrEnd - ptr, "RAW GPS: receiverIndex=%d, type=%d, count=%d %s",
1165  raw.receiverIndex, raw.dataType, raw.obsCount, terminator);
1166 
1167  if (m_displayMode != DMODE_SCROLL)
1168  {
1169  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
1170  }
1171  return buf;
1172 }
1173 
1175 {
1176  (void)hdr;
1177  char buf[BUF_SIZE];
1178  char* ptr = buf;
1179  char* ptrEnd = buf + BUF_SIZE;
1180 // int i = 0;
1181  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_SURVEY_IN:");
1182 
1183  ptr += SNPRINTF(ptr, ptrEnd - ptr, " state: %d ", survey.state);
1184  switch (survey.state)
1185  {
1186  case SURVEY_IN_STATE_OFF: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(off)"); break;
1187  case SURVEY_IN_STATE_RUNNING_3D: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(running 3D)"); break;
1188  case SURVEY_IN_STATE_RUNNING_FLOAT: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(running Float)"); break;
1189  case SURVEY_IN_STATE_RUNNING_FIX: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(running Fix)"); break;
1190  case SURVEY_IN_STATE_SAVE_POS: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(saving pos)"); break;
1191  case SURVEY_IN_STATE_DONE: ptr += SNPRINTF(ptr, ptrEnd - ptr, "(done)"); break;
1192  }
1193 
1194  int elapsedTimeMin = survey.elapsedTimeSec / 60;
1195  int elapsedTimeSec = survey.elapsedTimeSec - (elapsedTimeMin * 60);
1196  int maxDurationMin = survey.maxDurationSec / 60;
1197  int maxDurationSec = survey.maxDurationSec - (maxDurationMin * 60);
1198 
1199  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", elapsed: %d:%02d of %2d:%02d",
1200  elapsedTimeMin, elapsedTimeSec, maxDurationMin, maxDurationSec );
1201  if (m_displayMode != DMODE_SCROLL)
1202  {
1203  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n\thAcc: %4.3f\tlla:", survey.hAccuracy);
1204  ptr += SNPRINTF(ptr, ptrEnd - ptr, PRINTV3_LLA,
1205  survey.lla[0], // latitude
1206  survey.lla[1], // longitude
1207  survey.lla[2]); // altitude
1208  }
1209  else
1210  { // Single line format
1211  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", hAcc: %4.3f ", survey.hAccuracy);
1212  ptr += SNPRINTF(ptr, ptrEnd - ptr, " lla[%12.7f,%12.7f,%7.1f]",
1213  survey.lla[0], // latitude
1214  survey.lla[1], // longitude
1215  survey.lla[2]); // altitude
1216  }
1217  return buf;
1218 }
1219 
1221 {
1222  (void)hdr;
1223  char buf[BUF_SIZE];
1224  char* ptr = buf;
1225  char* ptrEnd = buf + BUF_SIZE;
1226  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_SYS_PARAMS:");
1227 
1228 #if DISPLAY_DELTA_TIME==1
1229  static int lastTimeMs = 0;
1230  int dtMs = sys.timeOfWeekMs - lastTimeMs;
1231  lastTimeMs = sys.timeOfWeekMs;
1232  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %3dms", dtMs);
1233 #else
1234  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %dms", sys.timeOfWeekMs);
1235 #endif
1236 
1237  ptr += SNPRINTF(ptr, ptrEnd - ptr, ",%d,%d,%d\n", sys.imuPeriodMs, sys.navPeriodMs, sys.genFaultCode);
1238 
1239  if (m_displayMode == DMODE_PRETTY)
1240  {
1241  ptr = StatusToString(ptr, ptrEnd, sys.insStatus, sys.hdwStatus);
1242  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\tTemp: IMU %4.1f C\tBaro %4.1f C\tMCU %4.1f C\n", sys.imuTemp, sys.baroTemp, sys.mcuTemp);
1243  }
1244 
1245  return buf;
1246 }
1247 
1249 {
1250  (void)hdr;
1251  char buf[BUF_SIZE];
1252  char* ptr = buf;
1253  char* ptrEnd = buf + BUF_SIZE;
1254  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_SYS_SENSORS:");
1255 
1256 #if DISPLAY_DELTA_TIME==1
1257  static double lastTime = 0;
1258  double dtMs = 1000.0*(sensors.time - lastTime);
1259  lastTime = sensors.time;
1260  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %4.1lfms", dtMs);
1261 #else
1262  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %.3lfs", sensors.time);
1263 #endif
1264 
1265  // Single line format
1266  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", %4.1fC, pqr[%5.1f,%5.1f,%5.1f], acc[%5.1f,%5.1f,%5.1f], mag[%6.2f,%6.2f,%6.2f]",
1267  sensors.temp,
1268  sensors.pqr[0] * C_RAD2DEG_F,
1269  sensors.pqr[1] * C_RAD2DEG_F,
1270  sensors.pqr[2] * C_RAD2DEG_F,
1271  sensors.acc[0], sensors.acc[1], sensors.acc[2],
1272  sensors.mag[0], sensors.mag[1], sensors.mag[2]
1273  );
1274 
1275  ptr += SNPRINTF(ptr, ptrEnd - ptr, ", baro[%5.2fkPa, %4.1fC, %7.2fm, %3.1f%% humidity], adc[%3.1fV, %3.1fV, %3.1fV, %3.1fV]",
1276  sensors.bar, sensors.barTemp, sensors.mslBar, sensors.humidity,
1277  sensors.vin, sensors.ana1, sensors.ana3, sensors.ana4
1278  );
1279 
1280  if (m_displayMode != DMODE_SCROLL)
1281  {
1282  ptr += SNPRINTF(ptr, ptrEnd - ptr, "\n");
1283  }
1284 
1285  return buf;
1286 }
1287 
1289 {
1290  cDataCSV csv;
1291  string csvString;
1292  csv.DataToStringCSV(hdr, (const uint8_t*)&info, csvString);
1293  const char* terminator = (m_displayMode != DMODE_SCROLL ? "\n" : "");
1294  return string("RTOS: ") + csvString + terminator;
1295 }
1296 
1298 {
1299  (void)hdr;
1300  char buf[BUF_SIZE];
1301  char* ptr = buf;
1302  char* ptrEnd = buf + BUF_SIZE;
1303  ptr += SNPRINTF(ptr, ptrEnd - ptr, "DID_DEV_INFO:");
1304 
1305  // Single line format
1306  ptr += SNPRINTF(ptr, ptrEnd - ptr, " SN%d, Fw %d.%d.%d.%d %c%d, %04d-%02d-%02d",
1307  info.serialNumber,
1308  info.firmwareVer[0],
1309  info.firmwareVer[1],
1310  info.firmwareVer[2],
1311  info.firmwareVer[3],
1312  info.buildDate[0],
1313  info.buildNumber,
1314  info.buildDate[1] + 2000,
1315  info.buildDate[2],
1316  info.buildDate[3]
1317  );
1318 
1319  if (m_displayMode != DMODE_SCROLL)
1320  { // Spacious format
1321  ptr += SNPRINTF(ptr, ptrEnd - ptr, " %02d:%02d:%02d, Proto %d.%d.%d.%d\n",
1322  info.buildTime[0],
1323  info.buildTime[1],
1324  info.buildTime[2],
1325  info.protocolVer[0],
1326  info.protocolVer[1],
1327  info.protocolVer[2],
1328  info.protocolVer[3]
1329  );
1330  }
1331 
1332  return buf;
1333 }
1334 
1336  (void) hdr; // hdr is not used
1337 
1338  stringstream ss;
1339  ss << "DID_SENSORS_ADC:";
1340  ss << fixed;
1341  ss << "time " << setprecision(3) << sensorsADC.time << ", ";
1342  ss << "bar " << setprecision(2) << sensorsADC.bar << ", ";
1343  ss << "barTemp " << setprecision(2) << sensorsADC.barTemp << ", ";
1344  ss << "humidity " << setprecision(2) << sensorsADC.humidity << ", ";
1345 
1346 // ss << " ana[" << setprecision(2);
1347 // for (size_t i = 0; i < NUM_ANA_CHANNELS; ++i)
1348 // {
1349 // if (i != 0) { ss << ", "; }
1350 // ss << sensorsADC.ana[i];
1351 // }
1352 // ss << "]";
1353 
1354  if (m_displayMode != DMODE_SCROLL)
1355  { // Spacious format
1356  ss << "\n";
1357 #define SADC_WIDTH 5
1358  for (size_t i = 0; i < NUM_IMU_DEVICES; ++i)
1359  {
1360  auto &mpu = sensorsADC.mpu[i];
1361  ss << "\tmpu[" << i << "]: " << setprecision(0);
1362  ss << "pqr[" << setw(SADC_WIDTH) << mpu.pqr[0] << "," << setw(SADC_WIDTH) << mpu.pqr[1] << "," << setw(SADC_WIDTH) << mpu.pqr[2] << "], ";
1363  ss << "acc[" << setw(SADC_WIDTH) << mpu.acc[0] << "," << setw(SADC_WIDTH) << mpu.acc[1] << "," << setw(SADC_WIDTH) << mpu.acc[2] << "], ";
1364  ss << "mag[" << setw(SADC_WIDTH) << mpu.mag[0] << "," << setw(SADC_WIDTH) << mpu.mag[1] << "," << setw(SADC_WIDTH) << mpu.mag[2] << "], ";
1365  ss << "temp " << setprecision(3) << mpu.temp << ",";
1366  ss << "\n";
1367  }
1368  }
1369  else
1370  {
1371  for (size_t i = 0; i < NUM_IMU_DEVICES; ++i)
1372  {
1373  auto &mpu = sensorsADC.mpu[i];
1374  ss << "mpu[" << i << "]: " << setprecision(0);
1375  ss << "pqr[" << mpu.pqr[0] << "," << mpu.pqr[1] << "," << mpu.pqr[2] << "], ";
1376  ss << "acc[" << mpu.acc[0] << "," << mpu.acc[1] << "," << mpu.acc[2] << "], ";
1377  ss << "mag[" << mpu.mag[0] << "," << mpu.mag[1] << "," << mpu.mag[2] << "], ";
1378  ss << "temp " << setprecision(3) << mpu.temp << ",";
1379  }
1380  }
1381 
1382  return ss.str();
1383 }
1384 
1385 
1386 ostream& boldOn(ostream& os)
1387 {
1388 
1389 #if PLATFORM_IS_WINDOWS
1390 
1391  return os;
1392 
1393 #else
1394 
1395  return os << "\033[1m";
1396 
1397 #endif
1398 
1399 }
1400 
1401 ostream& boldOff(ostream& os)
1402 {
1403 
1404 #if PLATFORM_IS_WINDOWS
1405 
1406  return os;
1407 
1408 #else
1409 
1410  return os << "\033[0m";
1411 
1412 #endif
1413 
1414 }
1415 
1416 // Bold on with newline
1417 ostream& endlbOn(ostream& os)
1418 {
1419 
1420 #if PLATFORM_IS_WINDOWS
1421 
1422  return os << endl;
1423 
1424 #else
1425 
1426  return os << endl << boldOn;
1427 
1428 #endif
1429 
1430 }
1431 
1432 // Bold off with newline
1433 ostream& endlbOff(ostream& os)
1434 {
1435 
1436 #if PLATFORM_IS_WINDOWS
1437 
1438  return os << endl;
1439 
1440 #else
1441 
1442  return os << endl << boldOff;
1443 
1444 #endif
1445 
1446 }
d
#define DID_SURVEY_IN
Definition: data_sets.h:107
gps_pos_t gpsPos
Definition: data_sets.h:3418
#define DID_DUAL_IMU
Definition: data_sets.h:92
static const char * GetDataSetName(uint32_t dataId)
imus_t I
Definition: data_sets.h:617
float bar
Definition: data_sets.h:653
float baseToRoverVector[3]
Definition: data_sets.h:2612
float humidity
Definition: data_sets.h:662
uint32_t recalCmd
Definition: data_sets.h:1332
ins_2_t ins2
Definition: data_sets.h:3407
gps_raw_t gpsRaw
Definition: data_sets.h:3430
float vDop
Definition: data_sets.h:2650
#define PRINTV3_LLA_MSL
Definition: ISDisplay.cpp:46
string DataToStringINS1(const ins_1_t &ins1, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:604
static void signalFunction(int sig)
Definition: ISDisplay.cpp:75
double towOffset
Definition: data_sets.h:774
#define PRINTV3_P3
Definition: ISDisplay.cpp:41
is_can_ve ve
Definition: CAN_comm.h:258
ostream & boldOn(ostream &os)
Definition: ISDisplay.cpp:1386
uint8_t arRatio
Definition: CAN_comm.h:232
void GoToColumnAndRow(int x, int y)
Definition: ISDisplay.cpp:186
float hAccuracy
Definition: data_sets.h:2858
float qn2b[4]
Definition: data_sets.h:534
float progress
Definition: data_sets.h:1335
float gDop
Definition: data_sets.h:2644
ins_1_t ins1
Definition: data_sets.h:3406
void ProcessData(p_data_t *data, bool enableReplay=false, double replaySpeedX=1.0)
Definition: ISDisplay.cpp:283
string DataToStringRawGPS(const gps_raw_t &raw, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1157
uint32_t elapsedTimeSec
Definition: data_sets.h:2855
float arThreshold
Definition: data_sets.h:2641
uint32_t id
Definition: ISComm.h:375
is_can_uvw uvw
Definition: CAN_comm.h:257
#define DID_INS_1
Definition: data_sets.h:38
string DataToStringSysSensors(const sys_sensors_t &sensors, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1248
string DataToStringSysParams(const sys_params_t &sys, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1220
uint32_t maxDurationSec
Definition: data_sets.h:2849
uint32_t state
Definition: data_sets.h:2846
#define DID_GPS2_RTK_CMP_REL
Definition: data_sets.h:125
#define printf(...)
void DataToStats(const p_data_t *data)
Definition: ISDisplay.cpp:472
XmlRpcServer s
float baroTemp
Definition: data_sets.h:1045
ostream & endlbOff(ostream &os)
Definition: ISDisplay.cpp:1433
#define PRINTV3_LLA
Definition: ISDisplay.cpp:45
string DataToStringSensorsADC(const sys_sensors_adc_t &sensorsADC, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1335
sys_params_t sysParams
Definition: data_sets.h:3427
float mag[3]
Definition: data_sets.h:642
float timeOfWeekMs
Definition: CAN_comm.h:29
#define DID_COUNT
Definition: data_sets.h:138
#define DID_DEV_INFO
Definition: data_sets.h:35
dual_imu_t imu
Definition: data_sets.h:696
#define DID_INS_2
Definition: data_sets.h:39
float barTemp
Definition: data_sets.h:659
string DataToStringMag(const magnetometer_t &mag, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:933
char * InsStatusToSolStatusString(char *ptr, char *ptrEnd, const uint32_t insStatus)
Definition: ISDisplay.cpp:587
char * StatusToString(char *ptr, char *ptrEnd, const uint32_t insStatus, const uint32_t hdwStatus)
Definition: ISDisplay.cpp:548
#define NULL
Definition: nm_bsp.h:52
char copyDataPToStructP(void *sptr, const p_data_t *data, const unsigned int maxsize)
Definition: ISComm.c:975
#define DID_PREINTEGRATED_IMU
Definition: data_sets.h:37
bool DataToStringCSV(const p_data_hdr_t &hdr, const uint8_t *buf, string &csv)
Definition: DataCSV.cpp:184
string DataToStringPreintegratedImu(const preintegrated_imu_t &imu, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:876
float ana4
Definition: data_sets.h:1010
double baseLla[3]
Definition: data_sets.h:2653
float pqr[3]
Definition: data_sets.h:603
#define NUM_IMU_DEVICES
Definition: data_sets.h:164
#define DID_SYS_PARAMS
Definition: data_sets.h:44
ostream & endlbOn(ostream &os)
Definition: ISDisplay.cpp:1417
#define SLEEP_MS(timeMs)
Definition: ISUtilities.h:134
uint8_t receiverIndex
Definition: data_sets.h:2791
string DataToString(const p_data_t *data)
Definition: ISDisplay.cpp:500
gps_rtk_misc_t gpsRtkMisc
Definition: data_sets.h:3422
#define DID_GPS_BASE_RAW
Definition: data_sets.h:94
int16_t theta1
Definition: CAN_comm.h:48
#define DID_MAG_CAL
Definition: data_sets.h:53
mag_cal_t magCal
Definition: data_sets.h:3413
int16_t vel2
Definition: CAN_comm.h:191
ins_3_t ins3
Definition: data_sets.h:3408
unsigned long DWORD
Definition: integer.h:33
double timeOfWeek
Definition: data_sets.h:417
#define DID_MAGNETOMETER_2
Definition: data_sets.h:89
float baseToRoverDistance
Definition: data_sets.h:2615
int current_weekMs()
std::ostream & cout()
string DataToStringDualIMU(const dual_imu_t &imu, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:823
def hdwStatus(hstatus)
Hardware Status #####.
string DataToStringINS2(const ins_2_t &ins2, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:655
ostream & boldOff(ostream &os)
Definition: ISDisplay.cpp:1401
float pDop
Definition: data_sets.h:768
preintegrated_imu_t pImu
Definition: data_sets.h:3417
#define DID_GPS2_RAW
Definition: data_sets.h:104
#define BUF_SIZE
Definition: ISDisplay.cpp:47
uint32_t buildNumber
Definition: data_sets.h:451
string DataToStringBaro(const barometer_t &baro, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1001
float vin
Definition: data_sets.h:1001
string DataToStringINS3(const ins_3_t &ins3, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:711
uint32_t hdwStatus
Definition: CAN_comm.h:40
uint32_t cnoMean
Definition: CAN_comm.h:226
#define DID_GPS2_RTK_CMP_MISC
Definition: data_sets.h:126
float hDop
Definition: data_sets.h:2647
float mslBar
Definition: data_sets.h:656
#define DID_GPS1_RAW
Definition: data_sets.h:103
float declination
Definition: data_sets.h:1338
#define DID_GPS2_POS
Definition: data_sets.h:48
uint32_t genFaultCode
Definition: data_sets.h:1066
vector< string > m_didMsgs
Definition: ISDisplay.h:89
def quat2euler(q)
Definition: pose.py:126
#define C_RAD2DEG_F
Definition: ISConstants.h:562
ins_4_t ins4
Definition: data_sets.h:3409
static bool s_controlCWasPressed
Definition: ISDisplay.cpp:51
float baseToRoverHeading
Definition: data_sets.h:2618
uint8_t buildDate[4]
Definition: data_sets.h:463
double lla[3]
Definition: data_sets.h:511
int16_t theta2
Definition: CAN_comm.h:49
string DataToStringMagCal(const mag_cal_t &mag, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:971
p_data_hdr_t hdr
Definition: ISComm.h:388
uint32_t status
Definition: CAN_comm.h:114
sys_sensors_t sysSensors
Definition: data_sets.h:3428
#define DID_MAGNETOMETER_1
Definition: data_sets.h:86
#define SNPRINTF
Definition: ISConstants.h:146
#define INS_STATUS_SOLUTION(insStatus)
Definition: data_sets.h:213
dev_info_t devInfo
Definition: data_sets.h:3405
USBInterfaceDescriptor data
def insStatus(istatus)
INS Status #####.
int16_t vel1
Definition: CAN_comm.h:181
uint16_t dt
Definition: CAN_comm.h:174
#define PRINTV4_P3
Definition: ISDisplay.cpp:44
void qe2b2EulerNedEcef(Vector3 eul, const Vector4 qe2b, const Vector3d ecef)
Definition: ISPose.c:281
string DataToStringRtkMisc(const gps_rtk_misc_t &sol, const p_data_hdr_t &hdr, const string didName)
Definition: ISDisplay.cpp:1134
float acc[3]
Definition: data_sets.h:606
uint32_t insStatus
Definition: CAN_comm.h:37
sensors_mpu_w_temp_t mpu[NUM_IMU_DEVICES]
Definition: data_sets.h:1192
#define DID_GPS1_POS
Definition: data_sets.h:47
void ShowCursor(bool visible)
Definition: ISDisplay.cpp:108
float theta[3]
Definition: data_sets.h:505
#define DID_SYS_SENSORS
Definition: data_sets.h:45
#define DID_INS_3
Definition: data_sets.h:99
uint32_t serialNumber
Definition: data_sets.h:442
#define PRINTV3_P1
Definition: ISDisplay.cpp:39
string DataToStringGpsPos(const gps_pos_t &gps, const p_data_hdr_t &hdr, const string didName)
Definition: ISDisplay.cpp:1031
float ned[3]
Definition: data_sets.h:514
barometer_t baro
Definition: data_sets.h:3414
string DataToStringINS4(const ins_4_t &ins4, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:767
gps_rtk_rel_t gpsRtkRel
Definition: data_sets.h:3421
double ecef[3]
Definition: data_sets.h:420
float imuTemp
Definition: data_sets.h:1042
void DataToVector(const p_data_t *data)
Definition: ISDisplay.cpp:461
#define DID_GPS1_RTK_POS
Definition: data_sets.h:88
float ana1
Definition: data_sets.h:1004
eDisplayMode m_displayMode
Definition: ISDisplay.h:90
survey_in_t surveyIn
Definition: data_sets.h:3426
rtos_info_t rtosInfo
Definition: data_sets.h:3429
float ana3
Definition: data_sets.h:1007
uint8_t buildTime[4]
Definition: data_sets.h:466
uint8_t protocolVer[4]
Definition: data_sets.h:454
string DataToStringRTOS(const rtos_info_t &info, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1288
uint8_t firmwareVer[4]
Definition: data_sets.h:448
#define DID_GPS1_RTK_POS_REL
Definition: data_sets.h:55
float hAcc
Definition: data_sets.h:762
float vAcc
Definition: data_sets.h:765
float qe2b[4]
Definition: data_sets.h:589
float mcuTemp
Definition: data_sets.h:1048
float accuracyPos[3]
Definition: data_sets.h:2635
uint8_t obsCount
Definition: data_sets.h:2797
sys_sensors_adc_t sensorsAdc
Definition: data_sets.h:3431
is_can_time time
Definition: CAN_comm.h:252
uint8_t dataType
Definition: data_sets.h:2794
#define PRINTV3_P2
Definition: ISDisplay.cpp:40
uint8_t differentialAge
Definition: CAN_comm.h:234
#define HDW_STATUS_COM_PARSE_ERROR_COUNT(hdwStatus)
Definition: data_sets.h:330
vector< sDidStats > m_didStats
Definition: ISDisplay.h:100
uint32_t imuPeriodMs
Definition: data_sets.h:1054
#define DID_INS_4
Definition: data_sets.h:100
float temp
Definition: data_sets.h:977
uint32_t navPeriodMs
Definition: data_sets.h:1057
#define DID_BAROMETER
Definition: data_sets.h:87
#define DID_RTOS_INFO
Definition: data_sets.h:72
double lla[3]
Definition: data_sets.h:2861
string DataToStringSurveyIn(const survey_in_t &survey, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1174
#define DID_INL2_STATES
Definition: data_sets.h:82
#define SADC_WIDTH
string DataToStringDevInfo(const dev_info_t &info, const p_data_hdr_t &hdr)
Definition: ISDisplay.cpp:1297
string Replay(double speed=1.0)
Definition: ISDisplay.cpp:212
dual_imu_t dualImu
Definition: data_sets.h:3411
#define DID_GPS1_RTK_POS_MISC
Definition: data_sets.h:56
string DataToStringRtkRel(const gps_rtk_rel_t &gps, const p_data_hdr_t &hdr, const string didName)
Definition: ISDisplay.cpp:1096
#define DID_SENSORS_ADC
Definition: data_sets.h:62


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:04