ISLogger.cpp
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 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 <ctime>
14 #include <sstream>
15 #include <sys/types.h>
16 #include <sys/stat.h>
17 #include <algorithm>
18 #include <iomanip>
19 #include <iostream>
20 #include <stdio.h>
21 #include <stdlib.h>
22 #include <stddef.h>
23 #include <regex>
24 #include <set>
25 #include <sstream>
26 
27 #include "ISFileManager.h"
28 #include "ISLogger.h"
29 #include "ISDataMappings.h"
30 #include "ISLogFileFactory.h"
31 
32 #include "convert_ins.h"
33 
34 
35 #if PLATFORM_IS_EVB_2
36 #include "globals.h"
37 #include "rtc.h"
38 #endif
39 
40 #if PLATFORM_IS_LINUX || PLATFORM_IS_APPLE
41 
42 #include <sys/statvfs.h>
43 
44 #endif
45 
46 // #define DONT_CHECK_LOG_DATA_SET_SIZE // uncomment to allow reading in of new data logs into older code sets
47 
48 
49 const string cISLogger::g_emptyString;
50 
52 {
53  bool corrupt = (hdr != NULL &&
54  (
55  hdr->size == 0 ||
56  hdr->offset + hdr->size > MAX_DATASET_SIZE ||
57  hdr->id == 0 ||
58 // hdr->id >= DID_COUNT ||
59  hdr->offset % 4 != 0 ||
60  hdr->size % 4 != 0
61 // #if !defined(DONT_CHECK_LOG_DATA_SET_SIZE)
62 // || (cISDataMappings::GetSize(hdr->id) > 0 && hdr->offset + hdr->size > cISDataMappings::GetSize(hdr->id))
63 // #endif
64  ));
65  return corrupt;
66 }
67 
69 {
70  return (data != NULL && LogHeaderIsCorrupt(&data->hdr));
71 }
72 
74 {
75  m_enabled = false;
76  m_logStats = new cLogStats;
77  m_logStats->Clear();
79  m_lastCommTime = 0;
81 }
82 
83 
85 {
86  Cleanup();
88  delete m_logStats;
89 }
90 
91 
93 {
94  // Delete old devices
95  for (unsigned int i = 0; i < m_devices.size(); i++)
96  {
97  if (m_devices[i] != NULLPTR)
98  {
99  delete m_devices[i];
100  }
101  }
102  m_devices.clear();
103  m_logStats->Clear();
104 }
105 
106 
108 {
109  // if we have a timeout param and the time has elapsed, shutdown
110  if (m_lastCommTime == 0)
111  {
113  }
115  {
116  for (unsigned int i = 0; i < m_devices.size(); i++)
117  {
118  m_devices[i]->Flush();
119  }
120  }
121  ISFileManager::TouchFile(m_directory + "/stats.txt");
122 }
123 
124 
125 bool cISLogger::InitSaveCommon(eLogType logType, const string& directory, const string& subDirectory, int numDevices, float maxDiskSpacePercent, uint32_t maxFileSize, bool useSubFolderTimestamp)
126 {
127  static const int minFileCount = 50;
128  static const int maxFileCount = 10000;
129 
130  // Close any open files
131  CloseAllFiles();
132 
133  m_logType = logType;
134  m_directory = (directory.empty() ? DEFAULT_LOGS_DIRECTORY : directory);
135  maxDiskSpacePercent = _CLAMP(maxDiskSpacePercent, 0.01f, 0.99f);
136  uint64_t availableSpace = ISFileManager::GetDirectorySpaceAvailable(m_directory);
137  m_maxDiskSpace = (maxDiskSpacePercent <= 0.0f ? availableSpace : (uint64_t)(availableSpace * maxDiskSpacePercent));
138 
139  // ensure there are between min and max file count
140  if (maxFileSize > m_maxDiskSpace / minFileCount)
141  {
142  m_maxFileSize = (uint32_t)(m_maxDiskSpace / minFileCount);
143  }
144  else if (maxFileSize < m_maxDiskSpace / maxFileCount)
145  {
146  m_maxFileSize = (uint32_t)(m_maxDiskSpace / maxFileCount);
147  }
148  else
149  {
150  m_maxFileSize = maxFileSize;
151  }
152 
153  // create root dir
154  _MKDIR(m_directory.c_str());
155 
156  if (useSubFolderTimestamp)
157  {
158  // create time stamp dir
159  m_directory = directory + "/" + m_timeStamp;
160  _MKDIR(m_directory.c_str());
161 
162  if (!subDirectory.empty())
163  {
164  // create sub dir
165  m_directory += "/" + subDirectory;
166  _MKDIR(m_directory.c_str());
167  }
168  }
169 
170  // create empty stats file to track timestamps
171  string str = m_directory + "/" + subDirectory + "/stats.txt";
172  cISLogFileBase* statsFile = CreateISLogFile(str, "w");
173  CloseISLogFile(statsFile);
174 
175  // Initialize devices
176  return InitDevicesForWriting(numDevices);
177 }
178 
179 
181 {
182  char buf[80];
183 
184 #if PLATFORM_IS_EVB_2
185  date_time_t rtc;
186 #if USE_RTC_DATE_TIME // use RTC
187  rtc_get_date(RTC, &rtc.year, &rtc.month, &rtc.day, &rtc.week);
188  rtc_get_time(RTC, &rtc.hour, &rtc.minute, &rtc.second);
189 #else // use uINS GPS time
190  rtc = g_gps_date_time;
191 #endif
192  SNPRINTF(buf, _ARRAY_BYTE_COUNT(buf), "%.4d%.2d%.2d_%.2d%.2d%.2d",
193  (int)rtc.year, (int)rtc.month, (int)rtc.day,
194  (int)rtc.hour, (int)rtc.minute, (int)rtc.second);
195 #else
196  // Create timestamp
197  time_t rawtime = GetTime();
198  struct tm * timeinfo = localtime(&rawtime);
199  strftime(buf, 80, "%Y%m%d_%H%M%S", timeinfo);
200 #endif
201 
202  return string(buf);
203 }
204 
205 
206 bool cISLogger::InitSave(eLogType logType, const string& directory, int numDevices, float maxDiskSpacePercent, uint32_t maxFileSize, bool useSubFolderTimestamp)
207 {
209  return InitSaveCommon(logType, directory, g_emptyString, numDevices, maxDiskSpacePercent, maxFileSize, useSubFolderTimestamp);
210 }
211 
212 
213 bool cISLogger::InitSaveTimestamp(const string& timeStamp, const string& directory, const string& subDirectory, int numDevices, eLogType logType, float maxDiskSpacePercent, uint32_t maxFileSize, bool useSubFolderTimestamp)
214 {
215  if (timeStamp.length() == 0)
216  {
218  }
219  else
220  {
221  // Only use first 15 characters for the timestamp
222  m_timeStamp = timeStamp.substr(0, IS_LOG_TIMESTAMP_LENGTH);
223  }
224 
225  return InitSaveCommon(logType, directory, subDirectory, numDevices, maxDiskSpacePercent, maxFileSize, useSubFolderTimestamp);
226 }
227 
228 
230 {
231  Cleanup();
232 
233  // Add devices
234  m_devices.resize(numDevices);
235 
236  // Create and init new devices
237  for (int i = 0; i < numDevices; i++)
238  {
239  switch (m_logType)
240  {
241  default:
242  case LOGTYPE_DAT: m_devices[i] = new cDeviceLogSerial(); break;
243 #if !defined(PLATFORM_IS_EVB_2) || !PLATFORM_IS_EVB_2
244  case LOGTYPE_SDAT: m_devices[i] = new cDeviceLogSorted(); break;
245  case LOGTYPE_CSV: m_devices[i] = new cDeviceLogCSV(); break;
246  case LOGTYPE_JSON: m_devices[i] = new cDeviceLogJSON(); break;
247  case LOGTYPE_KML: m_devices[i] = new cDeviceLogKML(); break;
248 #endif
249  }
250 
251  m_devices[i]->InitDeviceForWriting(i, m_timeStamp, m_directory, m_maxDiskSpace, m_maxFileSize);
252  }
253 
254  m_errorFile = CreateISLogFile((m_directory + "/errors.txt"), "w");
255 
257 }
258 
259 bool cISLogger::LoadFromDirectory(const string& directory, eLogType logType, vector<string> serials)
260 {
261  // Delete and clear prior devices
262  Cleanup();
263  m_logType = logType;
264  string fileExtensionRegex;
265  set<string> serialNumbers;
266 
267  switch (logType)
268  {
269  default:
270  case cISLogger::LOGTYPE_DAT: fileExtensionRegex = "\\.dat$"; break;
271  case cISLogger::LOGTYPE_SDAT: fileExtensionRegex = "\\.sdat$"; break;
272  case cISLogger::LOGTYPE_CSV: fileExtensionRegex = "\\.csv$"; break;
273  case cISLogger::LOGTYPE_JSON: fileExtensionRegex = "\\.json$"; break;
274  case cISLogger::LOGTYPE_KML: return false; // fileExtensionRegex = "\\.kml$"; break; // kml read not supported
275  }
276 
277  // get all files, sorted by name
278  vector<ISFileManager::file_info_t> files;
279  ISFileManager::GetDirectorySpaceUsed(directory, fileExtensionRegex, files, false, false);
280  if (files.size() == 0)
281  {
282  return false;
283  }
284 
285  for (size_t i = 0; i < files.size(); i++)
286  {
287  string name = ISFileManager::GetFileName(files[i].name);
288 
289  // check for log file prefix
290  size_t endOfLogPrefixIndex = name.find(IS_LOG_FILE_PREFIX);
291  if (endOfLogPrefixIndex != string::npos)
292  {
293  endOfLogPrefixIndex += IS_LOG_FILE_PREFIX_LENGTH;
294  size_t serialNumberEndIndex = name.find('_', endOfLogPrefixIndex);
295  if (serialNumberEndIndex != string::npos)
296  {
297  string serialNumber = name.substr(endOfLogPrefixIndex, serialNumberEndIndex - endOfLogPrefixIndex);
298 
299  // if we don't have a timestamp yet, see if we can parse it from the filename, i.e. IS_LOG_FILE_PREFIX 30013_20170103_151023_001
300  if (m_timeStamp.length() == 0)
301  {
302  // find _ at end of timestamp
303  size_t timestampIndex = name.find_last_of('_');
304  if (timestampIndex == string::npos)
305  {
306  timestampIndex = name.find_last_of('.');
307  }
308  if (timestampIndex != string::npos && timestampIndex - ++serialNumberEndIndex == IS_LOG_TIMESTAMP_LENGTH)
309  {
310  m_timeStamp = name.substr(timestampIndex - IS_LOG_TIMESTAMP_LENGTH, IS_LOG_TIMESTAMP_LENGTH);
311  }
312  }
313 
314  // check for unique serial numbers
315  if (serialNumbers.find(serialNumber) == serialNumbers.end())
316  {
317  if (serials.size() == 0 || ((find(serials.begin(), serials.end(), "SN" + serialNumber) != serials.end() ||
318  find(serials.begin(), serials.end(), "ALL") != serials.end()))) // and that it is a serial number we want to use
319  {
320  serialNumbers.insert(serialNumber);
321 
322  // Add devices
323  switch (logType)
324  {
325  default:
326  case cISLogger::LOGTYPE_DAT: m_devices.push_back(new cDeviceLogSerial()); break;
327 #if !defined(PLATFORM_IS_EVB_2) || !PLATFORM_IS_EVB_2
328  case cISLogger::LOGTYPE_SDAT: m_devices.push_back(new cDeviceLogSorted()); break;
329  case cISLogger::LOGTYPE_CSV: m_devices.push_back(new cDeviceLogCSV()); break;
330  case cISLogger::LOGTYPE_JSON: m_devices.push_back(new cDeviceLogJSON()); break;
331 #endif
332  }
333  m_devices.back()->SetupReadInfo(directory, serialNumber, m_timeStamp);
334  }
335  }
336  }
337  }
338  }
339 
340  for (uint32_t i = 0; i < m_devices.size(); i++)
341  {
342  m_devices[i]->InitDeviceForReading();
343  }
344  return (m_devices.size() != 0);
345 }
346 
347 
348 bool cISLogger::LogData(unsigned int device, p_data_hdr_t* dataHdr, const uint8_t* dataBuf)
349 {
351 
352  if (!m_enabled)
353  {
354  m_errorFile->lprintf("Logger is not enabled\r\n");
355  return false;
356  }
357  else if (device >= m_devices.size() || dataHdr == NULL || dataBuf == NULL)
358  {
359  m_errorFile->lprintf("Invalid device handle or NULL data\r\n");
360  return false;
361  }
362  else if (LogHeaderIsCorrupt(dataHdr))
363  {
364  m_errorFile->lprintf("Corrupt log header, id: %lu, offset: %lu, size: %lu\r\n", (unsigned long)dataHdr->id, (unsigned long)dataHdr->offset, (unsigned long)dataHdr->size);
365  m_logStats->LogError(dataHdr);
366  }
367  else if (!m_devices[device]->SaveData(dataHdr, dataBuf))
368  {
369  m_errorFile->lprintf("Underlying log implementation failed to save\r\n");
370  m_logStats->LogError(dataHdr);
371  }
372 #if 1
373  else
374  {
375  double timestamp = cISDataMappings::GetTimestamp(dataHdr, dataBuf);
376  m_logStats->LogDataAndTimestamp(dataHdr->id, timestamp);
377 
378  if (dataHdr->id == DID_DIAGNOSTIC_MESSAGE)
379  {
380  // write to diagnostic text file
381 #if 0
382  std::ostringstream outFilePath;
383  outFilePath << m_directory << "/diagnostic_" << m_devices[device]->GetDeviceInfo()->serialNumber << ".txt";
384  cISLogFileBase *outfile = CreateISLogFile(outFilePath.str(), "a");
385 #else
386  cISLogFileBase *outfile = CreateISLogFile(m_directory + "/diagnostic_" + std::to_string(m_devices[device]->GetDeviceInfo()->serialNumber) + ".txt", "a");
387 #endif
388  std::string msg = (((diag_msg_t*)dataBuf)->message);
389  outfile->write(msg.c_str(), msg.length());
390  if (msg.length() > 0 && *msg.end() != '\n')
391  {
392  outfile->putch('\n');
393  }
394  CloseISLogFile(outfile);
395  }
396  }
397 #endif
398  return true;
399 }
400 
401 
402 p_data_t* cISLogger::ReadData(unsigned int device)
403 {
404  if (device >= m_devices.size())
405  {
406  return NULL;
407  }
408 
409  p_data_t* data = NULL;
410  while (LogDataIsCorrupt(data = m_devices[device]->ReadData()))
411  {
412  m_errorFile->lprintf("Corrupt log header, id: %lu, offset: %lu, size: %lu\r\n", (unsigned long)data->hdr.id, (unsigned long)data->hdr.offset, (unsigned long)data->hdr.size);
413  m_logStats->LogError(&data->hdr);
414  data = NULL;
415  }
416  if (data != NULL)
417  {
418  double timestamp = cISDataMappings::GetTimestamp(&data->hdr, data->buf);
419  m_logStats->LogDataAndTimestamp(data->hdr.id, timestamp);
420  }
421  return data;
422 }
423 
424 
425 p_data_t* cISLogger::ReadNextData(unsigned int& device)
426 {
427  while (device < m_devices.size())
428  {
429  p_data_t* data = ReadData(device);
430  if (data == NULL)
431  {
432  ++device;
433  }
434  }
435  return NULL;
436 }
437 
438 
440 {
441  for( unsigned int i = 0; i < m_devices.size(); i++ )
442  {
443  m_devices[i]->CloseAllFiles();
444  }
445 
446  m_logStats->WriteToFile(m_directory + "/stats.txt");
448 }
449 
450 
452 {
453  for (unsigned int i = 0; i < m_devices.size(); i++)
454  {
455  m_devices[i]->OpenWithSystemApp();
456  }
457 }
458 
459 
461 {
462  uint64_t size = 0;
463  for (size_t i = 0; i < m_devices.size(); i++)
464  {
465  size += m_devices[i]->LogSize();
466  }
467  return size;
468 }
469 
470 
471 uint64_t cISLogger::LogSize( unsigned int device )
472 {
473  if (device >= m_devices.size())
474  {
475  return 0;
476  }
477 
478  return m_devices[device]->LogSize();
479 }
480 
481 
483 {
484  return LogSizeAll() * 0.000001f;
485 }
486 
487 
488 float cISLogger::LogSizeMB( unsigned int device )
489 {
490  if (device >= m_devices.size())
491  {
492  return 0;
493  }
494 
495  return m_devices[device]->LogSize() * 0.000001f;
496 }
497 
498 
499 float cISLogger::FileSizeMB( unsigned int device )
500 {
501  if (device >= m_devices.size())
502  {
503  return 0;
504  }
505 
506  return m_devices[device]->FileSize() * 0.000001f;
507 }
508 
509 
510 uint32_t cISLogger::FileCount( unsigned int device )
511 {
512  if (device >= m_devices.size())
513  {
514  return 0;
515  }
516 
517  return m_devices[device]->FileCount();
518 }
519 
520 bool cISLogger::SetDeviceInfo(const dev_info_t *info, unsigned int device )
521 {
522  if (device >= m_devices.size() || info == NULL)
523  {
524  return false;
525  }
526 
527  m_devices[device]->SetDeviceInfo( info );
528  return true;
529 }
530 
531 const dev_info_t* cISLogger::GetDeviceInfo( unsigned int device )
532 {
533  if (device >= m_devices.size())
534  {
535  return NULL;
536  }
537 
538  return m_devices[device]->GetDeviceInfo();
539 }
540 
541 bool cISLogger::CopyLog(cISLogger& log, const string& timestamp, const string &outputDir, eLogType logType, float maxLogSpacePercent, uint32_t maxFileSize, bool useSubFolderTimestamp)
542 {
543  m_logStats->Clear();
544  if (!InitSaveTimestamp(timestamp, outputDir, g_emptyString, log.GetDeviceCount(), logType, maxLogSpacePercent, maxFileSize, useSubFolderTimestamp))
545  {
546  return false;
547  }
548  EnableLogging(true);
549  p_data_t* data = NULL;
550  for (unsigned int dev = 0; dev < log.GetDeviceCount(); dev++)
551  {
552  // Copy device info
553  const dev_info_t* devInfo = log.GetDeviceInfo(dev);
554  SetDeviceInfo(devInfo, dev);
555 
556  // Set KML configuration
558 
559  // Copy data
560  while ((data = log.ReadData(dev)))
561  {
562  // CSV special cases
563  if (logType == eLogType::LOGTYPE_CSV)
564  {
565  if (data->hdr.id == DID_INS_2)
566  { // Convert INS2 to INS1 when creating .csv logs
567  ins_1_t ins1;
568  ins_2_t ins2;
569 
570  copyDataPToStructP(&ins2, data, sizeof(ins_2_t));
571  convertIns2ToIns1(&ins2, &ins1);
572 
573  p_data_hdr_t hdr;
574  hdr.id = DID_INS_1;
575  hdr.size = sizeof(ins_1_t);
576  hdr.offset = 0;
577  LogData(dev, &hdr, (uint8_t*)&ins1);
578  }
579  }
580 
581  // Save data
582  LogData(dev, &data->hdr, data->buf);
583  }
584  }
585  CloseAllFiles();
586  return true;
587 }
588 
589 bool cISLogger::ReadAllLogDataIntoMemory(const string& directory, map<uint32_t, vector<vector<uint8_t>>>& data)
590 {
591  cISLogger logger;
592  if (!logger.LoadFromDirectory(directory))
593  {
594  return false;
595  }
596  unsigned int deviceId = 0;
597  unsigned int lastDeviceId = 0xFFFFFEFE;
598  p_data_t* p;
599  vector<vector<uint8_t>>* currentDeviceData = NULL;
600  const dev_info_t* info;
601  uint8_t* ptr, *ptrEnd;
602  data.clear();
603 
604  // read every piece of data out of every device log
605  while ((p = logger.ReadNextData(deviceId)) != NULL)
606  {
607  // if this is a new device, we need to add the device to the map using the serial number
608  if (deviceId != lastDeviceId)
609  {
610  lastDeviceId = deviceId;
611  info = logger.GetDeviceInfo(deviceId);
612  data[info->serialNumber] = vector<vector<uint8_t>>();
613  currentDeviceData = &data[info->serialNumber];
614  }
615 
616  assert(currentDeviceData != NULL);
617 
618  // add slots until we have slots at least equal to the data id
619  while (currentDeviceData->size() < p->hdr.id)
620  {
621  currentDeviceData->push_back(vector<uint8_t>());
622  }
623 
624  // append each byte of the packet to the slot
625  ptrEnd = p->buf + p->hdr.size;
626  vector<uint8_t>& stream = (*currentDeviceData)[p->hdr.id];
627  for (ptr = p->buf; ptr != ptrEnd; ptr++)
628  {
629  stream.push_back(*ptr);
630  }
631  }
632  return true;
633 }
634 
636 {
637  count = 0;
638  errorCount = 0;
639  averageTimeDelta = 0.0;
640  totalTimeDelta = 0.0;
641  lastTimestamp = 0.0;
642  lastTimestampDelta = 0.0;
643  maxTimestampDelta = 0.0;
644  minTimestampDelta = 1.0E6;
645  timestampDeltaCount = 0;
646  timestampDropCount = 0;
647 }
648 
649 void cLogStatDataId::LogTimestamp(double timestamp)
650 {
651  // check for corrupt data
652  if (_ISNAN(timestamp) || timestamp < 0.0 || timestamp > 999999999999.0)
653  {
654  return;
655  }
656  else if (lastTimestamp > 0.0)
657  {
658  double delta = fabs(timestamp - lastTimestamp);
659  minTimestampDelta = _MIN(delta, minTimestampDelta);
660  maxTimestampDelta = _MAX(delta, maxTimestampDelta);
661  totalTimeDelta += delta;
662  averageTimeDelta = (totalTimeDelta / (double)++timestampDeltaCount);
663  if (lastTimestampDelta != 0.0 && (fabs(delta - lastTimestampDelta) > (lastTimestampDelta * 0.5)))
664  {
665  timestampDropCount++;
666  }
667  lastTimestampDelta = delta;
668  }
669  lastTimestamp = timestamp;
670 }
671 
673 {
674 
675 #if !PLATFORM_IS_EMBEDDED
676 
677  printf(" Count: %llu, Errors: %llu\r\n", (unsigned long long)count, (unsigned long long)errorCount);
678  printf(" Time delta: (ave, min, max) %f, %f, %f\r\n", averageTimeDelta, minTimestampDelta, maxTimestampDelta);
679  printf(" Time delta drop: %llu\r\n", (unsigned long long)timestampDropCount);
680 
681 #endif
682 
683 }
684 
686 {
687  Clear();
688 }
689 
691 {
692  memset(dataIdStats, 0, sizeof(dataIdStats));
693  for (uint32_t id = 0; id < DID_COUNT; id++)
694  {
695  dataIdStats[id].minTimestampDelta = 1.0E6;
696  }
697  errorCount = 0;
698  count = 0;
699 }
700 
702 {
703  errorCount++;
704  if (hdr != NULL && hdr->id < DID_COUNT)
705  {
706  cLogStatDataId& d = dataIdStats[hdr->id];
707  d.errorCount++;
708  }
709 }
710 
711 void cLogStats::LogData(uint32_t dataId)
712 {
713  if (dataId < DID_COUNT)
714  {
715  cLogStatDataId& d = dataIdStats[dataId];
716  d.count++;
717  count++;
718  }
719 }
720 
721 void cLogStats::LogDataAndTimestamp(uint32_t dataId, double timestamp)
722 {
723  if (dataId < DID_COUNT)
724  {
725  cLogStatDataId& d = dataIdStats[dataId];
726  d.count++;
727  count++;
728  if (timestamp != 0.0)
729  {
730  d.LogTimestamp(timestamp);
731  }
732  }
733 }
734 
736 {
737 
738 #if !PLATFORM_IS_EMBEDDED
739 
740  printf("LOG STATS\r\n");
741  printf("----------");
742  printf("Count: %llu, Errors: %llu\r\n", (unsigned long long)count, (unsigned long long)errorCount);
743  for (uint32_t id = 0; id < DID_COUNT; id++)
744  {
745  if (dataIdStats[id].count != 0)
746  {
747  printf(" DID: %d\r\n", id);
748  dataIdStats[id].Printf();
749  printf("\r\n");
750  }
751  }
752 
753 #endif
754 
755 }
756 
757 void cLogStats::WriteToFile(const string &file_name)
758 {
759  if (count != 0)
760  {
761  // flush log stats to disk
762 #if 1
763  cISLogFileBase *statsFile = CreateISLogFile(file_name, "wb");
764  statsFile->lprintf("Total count: %d, Total errors: \r\n\r\n", count, errorCount);
765  for (uint32_t id = 0; id < DID_COUNT; id++)
766  {
767  cLogStatDataId& stat = dataIdStats[id];
768  if (stat.count == 0 && stat.errorCount == 0)
769  { // Exclude zero count stats
770  continue;
771  }
772 
773  statsFile->lprintf("Data Id: %d (%s)\r\n", id, cISDataMappings::GetDataSetName(id));
774  statsFile->lprintf("Count: %d, Errors: %d\r\n", stat.count, stat.errorCount);
775  statsFile->lprintf("Timestamp Delta (ave, min, max): %.4f, %.4f, %.4f\r\n", stat.averageTimeDelta, stat.minTimestampDelta, stat.maxTimestampDelta);
776  statsFile->lprintf("Timestamp Drops: %d\r\n", stat.timestampDropCount);
777  statsFile->lprintf("\r\n");
778  }
779  CloseISLogFile(statsFile);
780 #else
781  // The following code doesn't work on the EVB-2. Converting stringstream to a string causes the system to hang.
782  CONST_EXPRESSION char CRLF[]= "\r\n";
783  stringstream stats;
784  stats << fixed << setprecision(6);
785  stats << "Total count: " << count << ", Total errors: " << errorCount << CRLF << CRLF;
786  for (uint32_t id = 0; id < DID_COUNT; id++)
787  {
788  cLogStatDataId& stat = dataIdStats[id];
789  if (stat.count == 0 && stat.errorCount == 0)
790  { // Exclude zero count stats
791  continue;
792  }
793 
794  stats << "Data Id: " << id << " (" << cISDataMappings::GetDataSetName(id) << ")" << CRLF;
795  stats << "Count: " << stat.count << ", Errors: " << stat.errorCount << CRLF;
796  stats << "Timestamp Delta (ave, min, max): " << stat.averageTimeDelta << ", " << stat.minTimestampDelta << ", " << stat.maxTimestampDelta << CRLF;
797  stats << "Timestamp Drops: " << stat.timestampDropCount << CRLF;
798  stats << CRLF;
799  }
800  cISLogFileBase *statsFile = CreateISLogFile(file_name, "wb");
801  statsFile->puts(stats.str().c_str());
802  CloseISLogFile(statsFile);
803 #endif
804  }
805 }
#define _MIN(a, b)
Definition: ISConstants.h:298
void CloseAllFiles()
Definition: ISLogger.cpp:439
d
static const char * GetDataSetName(uint32_t dataId)
vector< cDeviceLog * > m_devices
Definition: ISLogger.h:179
void convertIns2ToIns1(ins_2_t *ins2, ins_1_t *result)
Definition: convert_ins.cpp:18
bool InitSave(eLogType logType=LOGTYPE_DAT, const string &directory=g_emptyString, int numDevices=1, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, bool useSubFolderTimestamp=true)
Definition: ISLogger.cpp:206
bool CopyLog(cISLogger &log, const string &timestamp=g_emptyString, const string &outputDir=g_emptyString, eLogType logType=LOGTYPE_DAT, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, bool useSubFolderTimestamp=true)
Definition: ISLogger.cpp:541
void Cleanup()
Definition: ISLogger.cpp:92
bool InitDevicesForWriting(int numDevices=1)
Definition: ISLogger.cpp:229
uint32_t FileCount(unsigned int device=0)
Definition: ISLogger.cpp:510
void LogTimestamp(double timestamp)
Definition: ISLogger.cpp:649
static bool ReadAllLogDataIntoMemory(const string &directory, map< uint32_t, vector< vector< uint8_t >>> &data)
Definition: ISLogger.cpp:589
float LogSizeMB(unsigned int device=0)
Definition: ISLogger.cpp:488
uint32_t second
Definition: globals.h:40
uint32_t id
Definition: ISComm.h:376
#define DID_INS_1
Definition: data_sets.h:38
uint32_t GetDeviceCount()
Definition: ISLogger.h:88
uint64_t timestampDropCount
Definition: ISLogger.h:206
uint32_t size
Definition: ISComm.h:379
void rtc_get_time(Rtc *p_rtc, uint32_t *pul_hour, uint32_t *pul_minute, uint32_t *pul_second)
Get the RTC time value.
Definition: rtc.c:146
bool PathIsDir(const std::string &path)
void LogDataAndTimestamp(uint32_t dataId, double timestamp)
Definition: ISLogger.cpp:721
size_t count(InputIterator first, InputIterator last, T const &item)
Definition: catch.hpp:3206
struct PACKED ins_1_t
void LogData(uint32_t dataId)
Definition: ISLogger.cpp:711
#define DID_COUNT
Definition: data_sets.h:138
#define DID_INS_2
Definition: data_sets.h:39
void LogError(const p_data_hdr_t *hdr)
Definition: ISLogger.cpp:701
bool m_showPath
Definition: ISLogger.h:187
void OpenWithSystemApp()
Definition: ISLogger.cpp:451
#define NULL
Definition: nm_bsp.h:52
char copyDataPToStructP(void *sptr, const p_data_t *data, const unsigned int maxsize)
Definition: ISComm.c:975
virtual ~cISLogger()
Definition: ISLogger.cpp:84
time_t m_lastCommTime
Definition: ISLogger.h:190
uint64_t count
Definition: ISLogger.h:197
bool m_altClampToGround
Definition: ISLogger.h:185
void Printf()
Definition: ISLogger.cpp:735
cISLogFileBase * CreateISLogFile()
p_data_t * ReadData(unsigned int device=0)
Definition: ISLogger.cpp:402
#define DEFAULT_LOGS_DIRECTORY
Definition: ISLogger.h:43
void CloseISLogFile(cISLogFileBase *&logFile)
#define NULLPTR
Definition: ISConstants.h:426
const dev_info_t * GetDeviceInfo(unsigned int device=0)
Definition: ISLogger.cpp:531
#define CONST_EXPRESSION
Definition: ISConstants.h:411
#define _ISNAN(a)
Definition: ISConstants.h:318
virtual int lprintf(const char *format,...)=0
void EnableLogging(bool enabled)
Definition: ISLogger.h:76
bool LogData(unsigned int device, p_data_hdr_t *dataHdr, const uint8_t *dataBuf)
Definition: ISLogger.cpp:348
static double GetTimestamp(const p_data_hdr_t *hdr, const uint8_t *buf)
uint64_t GetDirectorySpaceAvailable(const std::string &directory)
cISLogFileBase * m_errorFile
Definition: ISLogger.h:183
static bool LogHeaderIsCorrupt(const p_data_hdr_t *hdr)
Definition: ISLogger.cpp:51
static bool LogDataIsCorrupt(const p_data_t *data)
Definition: ISLogger.cpp:68
uint32_t month
Definition: globals.h:40
#define printf(...)
Definition: evb_tasks.h:36
bool InitSaveTimestamp(const string &timeStamp, const string &directory=g_emptyString, const string &subDirectory=g_emptyString, int numDevices=1, eLogType logType=LOGTYPE_DAT, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, bool useSubFolderTimestamp=true)
Definition: ISLogger.cpp:213
uint32_t hour
Definition: globals.h:40
string m_timeStamp
Definition: ISLogger.h:178
void Update()
Definition: ISLogger.cpp:107
float LogSizeAllMB()
Definition: ISLogger.cpp:482
#define IS_LOG_FILE_PREFIX
Definition: DeviceLog.h:29
#define DID_DIAGNOSTIC_MESSAGE
Definition: data_sets.h:106
#define _ARRAY_BYTE_COUNT(a)
Definition: ISConstants.h:322
virtual int puts(const char *str)=0
void Clear()
Definition: ISLogger.cpp:690
p_data_hdr_t hdr
Definition: ISComm.h:389
uint32_t m_maxFileSize
Definition: ISLogger.h:181
double m_iconUpdatePeriodSec
Definition: ISLogger.h:189
float FileSizeMB(unsigned int device=0)
Definition: ISLogger.cpp:499
#define SNPRINTF
Definition: ISConstants.h:146
#define _CLAMP(v, minV, maxV)
Definition: ISConstants.h:302
date_time_t g_gps_date_time
Definition: globals.c:28
bool m_showTimeStamp
Definition: ISLogger.h:188
USBInterfaceDescriptor data
time_t m_timeoutFlushSeconds
Definition: ISLogger.h:191
#define _MAX(a, b)
Definition: ISConstants.h:294
bool InitSaveCommon(eLogType logType, const string &directory, const string &subDirectory, int numDevices, float maxDiskSpacePercent, uint32_t maxFileSize, bool useSubFolderTimestamp)
Definition: ISLogger.cpp:125
std::string GetFileName(const std::string &path)
uint32_t minute
Definition: globals.h:40
uint64_t m_maxDiskSpace
Definition: ISLogger.h:180
uint32_t serialNumber
Definition: data_sets.h:442
uint32_t year
Definition: globals.h:40
uint32_t week
Definition: globals.h:40
cLogStats * m_logStats
Definition: ISLogger.h:182
#define _MKDIR(dir)
Definition: ISConstants.h:213
bool LoadFromDirectory(const string &directory, eLogType logType=LOGTYPE_DAT, vector< string > serials={})
Definition: ISLogger.cpp:259
GeneratorWrapper< T > map(Func &&function, GeneratorWrapper< U > &&generator)
Definition: catch.hpp:3853
uint64_t GetDirectorySpaceUsed(const std::string &directory, bool recursive)
double maxTimestampDelta
Definition: ISLogger.h:204
double minTimestampDelta
Definition: ISLogger.h:203
static const string g_emptyString
Definition: ISLogger.h:59
bool SetDeviceInfo(const dev_info_t *info, unsigned int device=0)
Definition: ISLogger.cpp:520
uint32_t day
Definition: globals.h:40
void rtc_get_date(Rtc *p_rtc, uint32_t *pul_year, uint32_t *pul_month, uint32_t *pul_day, uint32_t *pul_week)
Get the RTC date value.
Definition: rtc.c:296
uint64_t LogSizeAll()
Definition: ISLogger.cpp:460
static string CreateCurrentTimestamp()
Definition: ISLogger.cpp:180
uint64_t LogSize(unsigned int device=0)
Definition: ISLogger.cpp:471
uint8_t buf[MAX_DATASET_SIZE]
Definition: ISComm.h:392
#define IS_LOG_TIMESTAMP_LENGTH
Definition: DeviceLog.h:31
double averageTimeDelta
Definition: ISLogger.h:199
string m_directory
Definition: ISLogger.h:177
uint32_t offset
Definition: ISComm.h:382
static time_t GetTime()
Definition: ISLogger.h:166
bool m_enabled
Definition: ISLogger.h:176
uint64_t errorCount
Definition: ISLogger.h:198
#define MAX_DATASET_SIZE
Definition: ISComm.h:91
eLogType m_logType
Definition: ISLogger.h:175
bool TouchFile(const std::string &path)
#define IS_LOG_FILE_PREFIX_LENGTH
Definition: DeviceLog.h:30
#define RTC
(RTC ) Base Address
Definition: same70j19.h:536
void WriteToFile(const string &fileName)
Definition: ISLogger.cpp:757
p_data_t * ReadNextData(unsigned int &device)
Definition: ISLogger.cpp:425
bool m_showSample
Definition: ISLogger.h:186


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:57