ISUtilities.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 <math.h>
16 #include <string>
17 
18 #include "ISUtilities.h"
19 #include "ISPose.h"
20 #include "ISEarth.h"
21 
22 #if PLATFORM_IS_EMBEDDED
23 
24 #include "../EVB-2/IS_EVB-2/src/drivers/d_time.h"
25 
26 #elif CPP11_IS_ENABLED
27 
28 #include <thread>
29 #include <mutex>
30 
31 #elif PLATFORM_IS_WINDOWS
32 
33 #include <windows.h>
34 #include <process.h>
35 
36 #elif PLATFORM_IS_LINUX
37 
38 
39 #else
40 
41 #error "Unsupported platform"
42 
43 #endif
44 
45 using namespace std;
46 
47 static const string s_base64_chars = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/";
48 static inline bool is_base64(unsigned char c)
49 {
50  return (isalnum(c) || (c == '+') || (c == '/'));
51 }
52 
53 string base64Encode(const unsigned char* bytes_to_encode, unsigned int in_len)
54 {
55  string ret;
56  int i = 0;
57  int j = 0;
58  unsigned char char_array_3[3];
59  unsigned char char_array_4[4];
60 
61  while (in_len--)
62  {
63  char_array_3[i++] = *(bytes_to_encode++);
64  if (i == 3)
65  {
66  char_array_4[0] = (char_array_3[0] & 0xfc) >> 2;
67  char_array_4[1] = ((char_array_3[0] & 0x03) << 4) + ((char_array_3[1] & 0xf0) >> 4);
68  char_array_4[2] = ((char_array_3[1] & 0x0f) << 2) + ((char_array_3[2] & 0xc0) >> 6);
69  char_array_4[3] = char_array_3[2] & 0x3f;
70  for (i = 0; (i < 4); i++)
71  {
72  ret += s_base64_chars[char_array_4[i]];
73  }
74  i = 0;
75  }
76  }
77 
78  if (i)
79  {
80  for (j = i; j < 3; j++)
81  {
82  char_array_3[j] = '\0';
83  }
84 
85  char_array_4[0] = (char_array_3[0] & 0xfc) >> 2;
86  char_array_4[1] = ((char_array_3[0] & 0x03) << 4) + ((char_array_3[1] & 0xf0) >> 4);
87  char_array_4[2] = ((char_array_3[1] & 0x0f) << 2) + ((char_array_3[2] & 0xc0) >> 6);
88  char_array_4[3] = char_array_3[2] & 0x3f;
89 
90  for (j = 0; (j < i + 1); j++)
91  {
92  ret += s_base64_chars[char_array_4[j]];
93  }
94 
95  while ((i++ < 3))
96  {
97  ret += '=';
98  }
99  }
100 
101  return ret;
102 
103 }
104 
105 string base64Decode(const string& encoded_string)
106 {
107  int in_len = (int)encoded_string.size();
108  int i = 0;
109  int j = 0;
110  int in_ = 0;
111  unsigned char char_array_4[4], char_array_3[3];
112  string ret;
113 
114  while (in_len-- && (encoded_string[in_] != '=') && is_base64(encoded_string[in_]))
115  {
116  char_array_4[i++] = encoded_string[in_];
117  in_++;
118  if (i == 4)
119  {
120  for (i = 0; i < 4; i++)
121  {
122  char_array_4[i] = (unsigned char)s_base64_chars.find(char_array_4[i]);
123  }
124  char_array_3[0] = (char_array_4[0] << 2) + ((char_array_4[1] & 0x30) >> 4);
125  char_array_3[1] = ((char_array_4[1] & 0xf) << 4) + ((char_array_4[2] & 0x3c) >> 2);
126  char_array_3[2] = ((char_array_4[2] & 0x3) << 6) + char_array_4[3];
127  for (i = 0; (i < 3); i++)
128  {
129  ret += char_array_3[i];
130  }
131  i = 0;
132  }
133  }
134 
135  if (i)
136  {
137  for (j = i; j < 4; j++)
138  {
139  char_array_4[j] = 0;
140  }
141  for (j = 0; j < 4; j++)
142  {
143  char_array_4[j] = (unsigned char)s_base64_chars.find(char_array_4[j]);
144  }
145  char_array_3[0] = (char_array_4[0] << 2) + ((char_array_4[1] & 0x30) >> 4);
146  char_array_3[1] = ((char_array_4[1] & 0xf) << 4) + ((char_array_4[2] & 0x3c) >> 2);
147  char_array_3[2] = ((char_array_4[2] & 0x3) << 6) + char_array_4[3];
148  for (j = 0; (j < i - 1); j++)
149  {
150  ret += char_array_3[j];
151  }
152  }
153 
154  return ret;
155 }
156 
157 size_t splitString(const string& s, const string& delimiter, vector<string>& result)
158 {
159  result.clear();
160  size_t pos = 0;
161  size_t pos2;
162  while (true)
163  {
164  pos2 = s.find(delimiter, pos);
165  if (pos2 == string::npos)
166  {
167  result.push_back(s.substr(pos));
168  break;
169  }
170  else
171  {
172  result.push_back(s.substr(pos, pos2 - pos));
173  pos = pos2 + delimiter.length();
174  }
175  }
176  return result.size();
177 }
178 
179 #ifdef __cplusplus
180 extern "C" {
181 #endif
182 
183 #if PLATFORM_IS_WINDOWS
184 
185  void usleep(__int64 usec)
186  {
187  HANDLE timer;
188  LARGE_INTEGER ft;
189 
190  ft.QuadPart = -(10 * usec); // Convert to 100 nanosecond interval, negative value indicates relative time
191 
192  timer = CreateWaitableTimer(NULL, true, NULL);
193  SetWaitableTimer(timer, &ft, 0, NULL, NULL, 0);
194  WaitForSingleObject(timer, INFINITE);
195  CloseHandle(timer);
196  }
197 
198 #else
199 
200 #include <unistd.h>
201 #include <sys/time.h>
202 
203 #endif
204 
206 {
207 
208 #if PLATFORM_IS_WINDOWS
209 
210  SYSTEMTIME st;
211  GetLocalTime(&st);
212  return st.wSecond;
213 
214 #else
215 
216  struct timeval tv;
217  gettimeofday(&tv, NULL);
218  return tv.tv_sec;
219 
220 #endif
221 
222 }
223 
225 {
226 
227 #if PLATFORM_IS_WINDOWS
228 
229  SYSTEMTIME st;
230  GetSystemTime(&st);
231  return st.wMilliseconds;
232 
233 #else
234 
235  struct timeval tv;
236  gettimeofday(&tv, NULL);
237  return tv.tv_usec / 1000;
238 
239 #endif
240 
241 }
242 
245 {
246 
247 #if PLATFORM_IS_WINDOWS
248 
249  SYSTEMTIME st;
250  GetSystemTime(&st);
251  return st.wMilliseconds + 1000 * (st.wSecond + 60 * (st.wMinute + 60 * (st.wHour + 24 * st.wDayOfWeek)));
252 
253 #else
254 
255  struct timeval tv;
256  gettimeofday(&tv, NULL);
257  return tv.tv_usec / 1000 + 1000 * tv.tv_sec;
258 
259 #endif
260 
261 }
262 
263 uint64_t current_weekUs()
264 {
265 
266 #if PLATFORM_IS_WINDOWS
267 
268  LARGE_INTEGER StartingTime;
269  LARGE_INTEGER Frequency;
270 
271  QueryPerformanceCounter(&StartingTime);
272  QueryPerformanceFrequency(&Frequency);
273 
274  StartingTime.QuadPart *= 1000000;
275  StartingTime.QuadPart /= Frequency.QuadPart;
276 
277  return StartingTime.QuadPart;
278 
279 #else
280 
281  struct timeval tv;
282  gettimeofday(&tv, NULL);
283  return tv.tv_usec + 1000000 * tv.tv_sec;
284 
285 #endif
286 
287 }
288 
289 uint64_t timerUsStart()
290 {
291 
292 #if PLATFORM_IS_WINDOWS
293 
294  LARGE_INTEGER StartingTime;
295  QueryPerformanceCounter(&StartingTime);
296  return StartingTime.QuadPart;
297 
298 #else
299 
300  struct timeval tv;
301  gettimeofday(&tv, NULL);
302  return tv.tv_usec + 1000000 * tv.tv_sec;
303 
304 #endif
305 
306 }
307 
308 uint64_t timerUsEnd(uint64_t start)
309 {
310 
311 #if PLATFORM_IS_WINDOWS
312 
313  LARGE_INTEGER EndingTime, ElapsedTimeUs;
314  LARGE_INTEGER Frequency;
315 
316  QueryPerformanceCounter(&EndingTime);
317  QueryPerformanceFrequency(&Frequency);
318 
319  ElapsedTimeUs.QuadPart = EndingTime.QuadPart - start;
320 
321  ElapsedTimeUs.QuadPart *= 1000000;
322  ElapsedTimeUs.QuadPart /= Frequency.QuadPart;
323 
324  return ElapsedTimeUs.QuadPart;
325 
326 #else
327 
328  struct timeval tv;
329  gettimeofday(&tv, NULL);
330  uint64_t stopTimeUs = tv.tv_usec + 1000000 * tv.tv_sec;
331  return stopTimeUs - start;
332 
333 #endif
334 
335 }
336 
337 uint64_t timerRawStart()
338 {
339 
340 #if PLATFORM_IS_WINDOWS
341 
342  LARGE_INTEGER StartingTime;
343  QueryPerformanceCounter(&StartingTime);
344  return StartingTime.QuadPart;
345 
346 #else
347 
348  struct timeval tv;
349  gettimeofday(&tv, NULL);
350  return tv.tv_usec + 1000000 * tv.tv_sec;
351 
352 #endif
353 
354 }
355 
356 uint64_t timerRawEnd(uint64_t start)
357 {
358 
359 #if PLATFORM_IS_WINDOWS
360 
361  LARGE_INTEGER EndingTime, ElapsedTimeUs;
362  QueryPerformanceCounter(&EndingTime);
363  ElapsedTimeUs.QuadPart = EndingTime.QuadPart - start;
364  return ElapsedTimeUs.QuadPart;
365 
366 #else
367 
368  struct timeval tv;
369  gettimeofday(&tv, NULL);
370  uint64_t stopTimeUs = tv.tv_usec + 1000000 * tv.tv_sec;
371  return stopTimeUs - start;
372 
373 #endif
374 
375 }
376 
377 uint64_t getTickCount(void)
378 {
379 
380 #if PLATFORM_IS_WINDOWS
381 
382  return GetTickCount64();
383 
384 #elif PLATFORM_IS_EVB_2
385 
386  return time_ticks();
387 
388 #else
389 
390  struct timespec now;
391  if (clock_gettime(CLOCK_MONOTONIC, &now))
392  {
393  return 0;
394  }
395  return (uint64_t)(now.tv_sec * 1000.0 + now.tv_nsec / 1000000.0);
396 
397 #endif
398 
399 }
400 
401 int bootloadUploadProgress(const void* port, float percent)
402 {
403  // Suppress compiler warnings
404  (void)port;
405 
406  printf("\rUpload: %d%% \r", (int)(percent * 100.0f));
407  if (percent == 1.0f)
408  {
409  printf("\r\n");
410  }
411  fflush(stdout); // stdout stream is buffered (in Linux) so output is only seen after a newline '\n' or fflush().
412 
413  return 1; // could return 0 to abort
414 }
415 
416 int bootloadVerifyProgress(const void* port, float percent)
417 {
418  // Suppress compiler warnings
419  (void)port;
420 
421  printf("\rVerify: %d%% \r", (int)(percent * 100.0f));
422  if (percent == 1.0f)
423  {
424  printf("\r\n");
425  }
426  fflush(stdout); // stdout stream is buffered (in Linux) so output is only seen after a newline '\n' or fflush().
427 
428  return 1; // could return 0 to abort
429 }
430 
431 void bootloadStatusInfo(const void* port, const char* str)
432 {
433  (void)port;
434  cout << str << endl;
435 }
436 
437 float step_sinwave(float *sig_gen, float freqHz, float amplitude, float periodSec)
438 {
439  *sig_gen += freqHz * periodSec * C_TWOPI_F;
440 
441  // Unwrap Angle
442  if (*sig_gen > C_PI_F)
443  {
444  *sig_gen -= C_TWOPI_F;
445  }
446 
447  return amplitude * sinf(*sig_gen);
448 }
449 
450 FILE* openFile(const char* path, const char* mode)
451 {
452  FILE* file = 0;
453 
454 #ifdef _MSC_VER
455 
456  fopen_s(&file, path, mode);
457 
458 #else
459 
460  file = fopen(path, mode);
461 
462 #endif
463 
464  return file;
465 
466 }
467 
468 const char* tempPath()
469 {
470 
471 #if PLATFORM_IS_WINDOWS
472 
473  static char _tempPath[MAX_PATH];
474  if (_tempPath[0] == 0)
475  {
476  GetTempPathA(MAX_PATH, _tempPath);
477  }
478  return _tempPath;
479 
480 #else
481 
482  return "/tmp/";
483 
484 #endif
485 
486 }
487 
488 const unsigned char* getHexLookupTable()
489 {
490  static const unsigned char s_hexLookupTable[16] = { '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
491  return s_hexLookupTable;
492 }
493 
494 uint8_t getHexValue(unsigned char hex)
495 {
496  return 9 * (hex >> 6) + (hex & 017);
497 }
498 
499 void* threadCreateAndStart(void(*function)(void* info), void* info)
500 {
501 #if PLATFORM_IS_EMBEDDED
502 
503  return NULLPTR;
504 
505 #elif CPP11_IS_ENABLED
506 
507  return new thread(function, info);
508 
509 #elif PLATFORM_IS_WINDOWS
510 
511  return CreateThread(NULL, 0, (LPTHREAD_START_ROUTINE)function, info, 0, NULL);
512 
513 #else
514 
515  pthread_t* t = (pthread_t*)MALLOC(sizeof(pthread_t));
516  pthread_create(t, NULL, function, info);
517  return t;
518 
519 #endif
520 
521 }
522 
523 void threadJoinAndFree(void* handle)
524 {
525  if (handle == NULL)
526  {
527  return;
528  }
529 
530 #if PLATFORM_IS_EMBEDDED
531 
532  return;
533 
534 #elif CPP11_IS_ENABLED
535 
536  ((thread*)handle)->join();
537  delete (thread*)handle;
538 
539 #elif PLATFORM_IS_WINDOWS
540 
541  WaitForSingleObject(handle, 0);
542  CloseHandle(handle);
543 
544 #else
545 
546  pthread_join((pthread_t*)handle);
547  FREE(handle);
548 
549 #endif
550 
551 }
552 
553 void* mutexCreate(void)
554 {
555 
556 #if PLATFORM_IS_EMBEDDED
557 
558  return NULLPTR;
559 
560 #elif CPP11_IS_ENABLED
561 
562  return new mutex();
563 
564 #elif PLATFORM_IS_WINDOWS
565 
566  CRITICAL_SECTION* c = (CRITICAL_SECTION*)MALLOC(sizeof(CRITICAL_SECTION));
567  InitializeCriticalSection(c);
568  return c;
569 
570 #else
571 
572  pthread_mutex_t* m = (pthread_mutex_t*)MALLOC(sizeof(pthread_mutex_t));
573  pthread_mutex_init(m, NULL);
574  return m;
575 
576 #endif
577 
578 }
579 
580 void mutexLock(void* handle)
581 {
582 
583 #if PLATFORM_IS_EMBEDDED
584 
585  return;
586 
587 #elif CPP11_IS_ENABLED
588 
589  ((mutex*)handle)->lock();
590 
591 #elif PLATFORM_IS_WINDOWS
592 
593  EnterCriticalSection((CRITICAL_SECTION*)handle);
594 
595 #else
596 
597  pthread_mutex_lock((pthread_mutex_t*)handle);
598 
599 #endif
600 
601 }
602 
603 void mutexUnlock(void* handle)
604 {
605 
606 #if PLATFORM_IS_EMBEDDED
607 
608  return;
609 
610 #elif CPP11_IS_ENABLED
611 
612  ((mutex*)handle)->unlock();
613 
614 #elif PLATFORM_IS_WINDOWS
615 
616  LeaveCriticalSection((CRITICAL_SECTION*)handle);
617 
618 #else
619 
620  pthread_mutex_unlock((pthread_mutex_t*)handle);
621 
622 #endif
623 
624 }
625 
626 void mutexFree(void* handle)
627 {
628  if (handle == NULL)
629  {
630  return;
631  }
632 
633 #if PLATFORM_IS_EMBEDDED
634 
635  return;
636 
637 #elif CPP11_IS_ENABLED
638 
639  delete (mutex*)handle;
640 
641 #elif PLATFORM_IS_WINDOWS
642 
643  DeleteCriticalSection((CRITICAL_SECTION*)handle);
644  FREE(handle);
645 
646 #else
647 
648  pthread_mutex_destroy((pthread_mutex_t*)handle);
649  FREE(handle);
650 
651 #endif
652 
653 }
654 
655 int32_t convertDateToMjd(int32_t year, int32_t month, int32_t day)
656 {
657  return
658  367 * year
659  - 7 * (year + (month + 9) / 12) / 4
660  - 3 * ((year + (month - 9) / 7) / 100 + 1) / 4
661  + 275 * month / 9
662  + day
663  + 1721028
664  - 2400000;
665 }
666 
667 int32_t convertGpsToMjd(int32_t gpsWeek, int32_t gpsSeconds)
668 {
669  uint32_t gpsDays = gpsWeek * 7 + (gpsSeconds / 86400);
670  return convertDateToMjd(1980, 1, 6) + gpsDays;
671 }
672 
673 void convertMjdToDate(int32_t mjd, int32_t* year, int32_t* month, int32_t* day)
674 {
675  int32_t j, c, y, m;
676 
677  j = mjd + 2400001 + 68569;
678  c = 4 * j / 146097;
679  j = j - (146097 * c + 3) / 4;
680  y = 4000 * (j + 1) / 1461001;
681  j = j - 1461 * y / 4 + 31;
682  m = 80 * j / 2447;
683  *day = j - 2447 * m / 80;
684  j = m / 11;
685  *month = m + 2 - (12 * j);
686  *year = 100 * (c - 49) + y + j;
687 }
688 
689 void convertGpsToHMS(int32_t gpsSeconds, int32_t* hour, int32_t* minutes, int32_t* seconds)
690 {
691  // shave off days
692  gpsSeconds = gpsSeconds % 86400;
693 
694  // compute hours, minutes, seconds
695  *hour = gpsSeconds / 3600;
696  *minutes = (gpsSeconds / 60) % 60;
697  *seconds = gpsSeconds % 60;
698 }
699 
700 uint32_t dateToWeekDay(uint32_t ul_year, uint32_t ul_month, uint32_t ul_day)
701 {
702  uint32_t ul_week;
703 
704  if (ul_month == 1 || ul_month == 2) {
705  ul_month += 12;
706  --ul_year;
707  }
708 
709  ul_week = (ul_day + 2 * ul_month + 3 * (ul_month + 1) / 5 + ul_year +
710  ul_year / 4 - ul_year / 100 + ul_year / 400) % 7;
711 
712  ++ul_week;
713 
714  return ul_week;
715 }
716 
717 gen_1axis_sensor_t gen1AxisSensorData(double time, const float val)
718 {
720  data.time = time;
721  data.val = val;
722  return data;
723 }
724 
725 gen_3axis_sensor_t gen3AxisSensorData(double time, const float val[3])
726 {
728  data.time = time;
729  data.val[0] = val[0];
730  data.val[1] = val[1];
731  data.val[2] = val[2];
732  return data;
733 }
734 
735 gen_dual_3axis_sensor_t genDual3AxisSensorData(double time, const float val1[3], const float val2[3])
736 {
738  data.time = time;
739  data.val1[0] = val1[0];
740  data.val1[1] = val1[1];
741  data.val1[2] = val1[2];
742  data.val2[0] = val2[0];
743  data.val2[1] = val2[1];
744  data.val2[2] = val2[2];
745  return data;
746 }
747 
748 gen_3axis_sensord_t gen3AxisSensorDataD(double time, const double val[3])
749 {
751  data.time = time;
752  data.val[0] = val[0];
753  data.val[1] = val[1];
754  data.val[2] = val[2];
755  return data;
756 }
757 
758 #ifdef __cplusplus
759 } // extern C
760 #endif
761 
762 cMutex::cMutex()
763 {
764  m_handle = mutexCreate();
765 }
766 
767 cMutex::~cMutex()
768 {
769  mutexFree(m_handle);
770 }
771 
772 void cMutex::Lock()
773 {
774  mutexLock(m_handle);
775 }
776 
777 void cMutex::Unlock()
778 {
779  mutexUnlock(m_handle);
780 }
781 
782 cMutexLocker::cMutexLocker(cMutex* mutex)
783 {
784  assert(mutex != NULLPTR);
785  m_mutex = mutex;
786  m_mutex->Lock();
787 }
788 
789 cMutexLocker::~cMutexLocker()
790 {
791  m_mutex->Unlock();
792 }
float val
Definition: data_sets.h:934
const char * tempPath()
void threadJoinAndFree(void *handle)
float step_sinwave(float *sig_gen, float freqHz, float amplitude, float periodSec)
Initialize signal generator.
f
float val2[3]
Definition: data_sets.h:957
void * threadCreateAndStart(void(*function)(void *info), void *info)
uint32_t dateToWeekDay(uint32_t ul_year, uint32_t ul_month, uint32_t ul_day)
#define printf(...)
uint64_t timerRawStart()
size_t splitString(const string &s, const string &delimiter, vector< string > &result)
int bootloadUploadProgress(const void *port, float percent)
uint64_t timerRawEnd(uint64_t start)
int bootloadVerifyProgress(const void *port, float percent)
#define NULL
Definition: nm_bsp.h:52
uint64_t getTickCount(void)
int32_t convertDateToMjd(int32_t year, int32_t month, int32_t day)
gen_1axis_sensor_t gen1AxisSensorData(double time, const float val)
#define NULLPTR
Definition: ISConstants.h:426
void mutexUnlock(void *handle)
void bootloadStatusInfo(const void *port, const char *str)
const unsigned char * getHexLookupTable()
#define FREE(m)
Definition: ISConstants.h:138
volatile uint64_t time_ticks(void)
Definition: d_time.c:65
int current_weekMs()
std::ostream & cout()
string base64Encode(const unsigned char *bytes_to_encode, unsigned int in_len)
Definition: ISUtilities.cpp:53
int current_timeMs()
FILE * openFile(const char *path, const char *mode)
uint8_t getHexValue(unsigned char hex)
uint64_t current_weekUs()
#define C_PI_F
Definition: ISConstants.h:554
static const string s_base64_chars
Definition: ISUtilities.cpp:47
uint64_t timerUsStart()
void convertMjdToDate(int32_t mjd, int32_t *year, int32_t *month, int32_t *day)
#define MALLOC(m)
Definition: ISConstants.h:136
USBInterfaceDescriptor data
gen_3axis_sensor_t gen3AxisSensorData(double time, const float val[3])
void * mutexCreate(void)
#define C_TWOPI_F
Definition: ISConstants.h:555
uint64_t timerUsEnd(uint64_t start)
static bool is_base64(unsigned char c)
Definition: ISUtilities.cpp:48
void mutexFree(void *handle)
int32_t convertGpsToMjd(int32_t gpsWeek, int32_t gpsSeconds)
int current_timeSec()
is_can_time time
Definition: CAN_comm.h:252
gen_dual_3axis_sensor_t genDual3AxisSensorData(double time, const float val1[3], const float val2[3])
float val1[3]
Definition: data_sets.h:954
void convertGpsToHMS(int32_t gpsSeconds, int32_t *hour, int32_t *minutes, int32_t *seconds)
string base64Decode(const string &encoded_string)
gen_3axis_sensord_t gen3AxisSensorDataD(double time, const double val[3])
void mutexLock(void *handle)


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