DataKML.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 <time.h>
15 #include <string>
16 #include <sstream>
17 #include <sys/types.h>
18 #include <sys/stat.h>
19 #include <iomanip>
20 #include <iostream>
21 #include <fstream>
22 #include <stdio.h>
23 #include <stdlib.h>
24 #include <stddef.h>
25 
26 #include "tinyxml.h"
27 #include "DataKML.h"
28 #include "ISLogger.h"
29 #include "ISPose.h"
30 #include "data_sets.h"
31 #include "ISUtilities.h"
32 #include "ISConstants.h"
33 
34 #ifdef USE_IS_INTERNAL
35 # include "../../cpp/libs/IS_internal.h"
36 #endif
37 
38 
40 {
41 // def[0].init( "devInfo", "Device information" );
42 // def[5].init( "ins2", "Inertial navigation data with quaternion attitude" );
43 }
44 
45 string cDataKML::GetDatasetName(int kid)
46 {
47  switch (kid)
48  {
49  default: return "";
50  case KID_INS: return "ins";
51  case KID_REF: return "ref";
52  case KID_GPS: return "gps";
53  case KID_GPS1: return "gps1";
54  case KID_GPS2: return "gps2";
55  case KID_RTK: return "rtk";
56  }
57 }
58 
59 
60 #include <inttypes.h>
61 #include <math.h>
62 #include <stdio.h>
63 #include <time.h>
64 
65 int cDataKML::WriteDataToFile(vector<sKmlLogData>& list, const p_data_hdr_t* dataHdr, const uint8_t* dataBuf)
66 {
67  uDatasets& d = (uDatasets&)(*dataBuf);
68  ixEuler theta;
70 
71 #ifdef USE_IS_INTERNAL
72 // uInternalDatasets &i = (uInternalDatasets&)(*dataBuf);
73 #endif
74 
75  // Write date to file
76  switch (dataHdr->id)
77  {
78  default: // Unidentified dataset
79  return 0;
80 
81  case DID_INS_1:
82  data = sKmlLogData(d.ins1.timeOfWeek, d.ins1.lla, d.ins1.theta);
83  break;
84  case DID_INS_2:
85  quat2euler(d.ins2.qn2b, theta);
86  data = sKmlLogData(d.ins2.timeOfWeek, d.ins2.lla, theta);
87  break;
88  case DID_INS_3:
89  quat2euler(d.ins3.qn2b, theta);
90  data = sKmlLogData(d.ins3.timeOfWeek, d.ins3.lla, theta);
91  break;
92  case DID_GPS1_POS:
93  case DID_GPS1_UBX_POS:
94  case DID_GPS2_POS:
96  break;
97  case DID_GPS1_RTK_POS:
99  break;
100  }
101 
102  list.push_back(data);
103 
104  return 0;
105 }
106 
107 
d
gps_pos_t gpsPos
Definition: data_sets.h:3540
ins_2_t ins2
Definition: data_sets.h:3529
string GetDatasetName(int kid)
Definition: DataKML.cpp:45
float qn2b[4]
Definition: data_sets.h:534
ins_1_t ins1
Definition: data_sets.h:3528
uint32_t id
Definition: ISComm.h:376
#define DID_INS_1
Definition: data_sets.h:38
cDataKML()
Definition: DataKML.cpp:39
#define DID_GPS1_UBX_POS
Definition: data_sets.h:40
float timeOfWeekMs
Definition: CAN_comm.h:29
#define DID_INS_2
Definition: data_sets.h:39
ins_3_t ins3
Definition: data_sets.h:3530
double timeOfWeek
Definition: data_sets.h:417
#define DID_GPS2_POS
Definition: data_sets.h:48
def quat2euler(q)
Definition: pose.py:126
int WriteDataToFile(vector< sKmlLogData > &list, const p_data_hdr_t *dataHdr, const uint8_t *dataBuf)
Definition: DataKML.cpp:65
double lla[3]
Definition: data_sets.h:511
ixVector3 ixEuler
Definition: ISConstants.h:797
USBInterfaceDescriptor data
#define DID_GPS1_POS
Definition: data_sets.h:47
float theta[3]
Definition: data_sets.h:505
#define DID_INS_3
Definition: data_sets.h:99
#define DID_GPS1_RTK_POS
Definition: data_sets.h:88


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