Line | Branch | Exec | Source |
---|---|---|---|
1 | // This file is part of INSTINCT, the INS Toolkit for Integrated | ||
2 | // Navigation Concepts and Training by the Institute of Navigation of | ||
3 | // the University of Stuttgart, Germany. | ||
4 | // | ||
5 | // This Source Code Form is subject to the terms of the Mozilla Public | ||
6 | // License, v. 2.0. If a copy of the MPL was not distributed with this | ||
7 | // file, You can obtain one at https://mozilla.org/MPL/2.0/. | ||
8 | |||
9 | #include "VectorNavBinaryConverter.hpp" | ||
10 | |||
11 | #include <cmath> | ||
12 | |||
13 | #include "util/Logger.hpp" | ||
14 | |||
15 | #include "internal/NodeManager.hpp" | ||
16 | namespace nm = NAV::NodeManager; | ||
17 | #include "internal/FlowManager.hpp" | ||
18 | |||
19 | #include "internal/gui/widgets/EnumCombo.hpp" | ||
20 | |||
21 | #include "Navigation/Transformations/CoordinateFrames.hpp" | ||
22 | #include "Navigation/Transformations/Units.hpp" | ||
23 | |||
24 | 144 | NAV::VectorNavBinaryConverter::VectorNavBinaryConverter() | |
25 |
2/4✓ Branch 1 taken 144 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 144 times.
✗ Branch 5 not taken.
|
144 | : Node(typeStatic()) |
26 | { | ||
27 | LOG_TRACE("{}: called", name); | ||
28 | 144 | _hasConfig = true; | |
29 | 144 | _guiConfigDefaultWindowSize = { 350, 123 }; | |
30 | |||
31 |
4/8✓ Branch 2 taken 144 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 144 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 144 times.
✓ Branch 10 taken 144 times.
✗ Branch 13 not taken.
✗ Branch 14 not taken.
|
576 | nm::CreateOutputPin(this, "ImuObs", Pin::Type::Flow, { NAV::ImuObsWDelta::type() }); |
32 | |||
33 |
4/8✓ Branch 1 taken 144 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 144 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 144 times.
✓ Branch 9 taken 144 times.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
|
432 | nm::CreateInputPin(this, "BinaryOutput", Pin::Type::Flow, { NAV::VectorNavBinaryOutput::type() }, &VectorNavBinaryConverter::receiveObs); |
34 | 432 | } | |
35 | |||
36 | 352 | NAV::VectorNavBinaryConverter::~VectorNavBinaryConverter() | |
37 | { | ||
38 | LOG_TRACE("{}: called", nameId()); | ||
39 | 352 | } | |
40 | |||
41 | 256 | std::string NAV::VectorNavBinaryConverter::typeStatic() | |
42 | { | ||
43 |
1/2✓ Branch 1 taken 256 times.
✗ Branch 2 not taken.
|
512 | return "VectorNavBinaryConverter"; |
44 | } | ||
45 | |||
46 | ✗ | std::string NAV::VectorNavBinaryConverter::type() const | |
47 | { | ||
48 | ✗ | return typeStatic(); | |
49 | } | ||
50 | |||
51 | 112 | std::string NAV::VectorNavBinaryConverter::category() | |
52 | { | ||
53 |
1/2✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
|
224 | return "Converter"; |
54 | } | ||
55 | |||
56 | ✗ | void NAV::VectorNavBinaryConverter::guiConfig() | |
57 | { | ||
58 | ✗ | if (gui::widgets::EnumCombo(fmt::format("Output Type##{}", size_t(id)).c_str(), _outputType)) | |
59 | { | ||
60 | ✗ | LOG_DEBUG("{}: Output Type changed to {}", nameId(), to_string(_outputType)); | |
61 | ✗ | if (_outputType == OutputType::ImuObs) | |
62 | { | ||
63 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::ImuObs::type() }; | |
64 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::ImuObs::type(); | |
65 | } | ||
66 | ✗ | else if (_outputType == OutputType::ImuObsWDelta) | |
67 | { | ||
68 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::ImuObsWDelta::type() }; | |
69 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::ImuObsWDelta::type(); | |
70 | } | ||
71 | ✗ | else if (_outputType == OutputType::PosVelAtt) | |
72 | { | ||
73 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::PosVelAtt::type() }; | |
74 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::PosVelAtt::type(); | |
75 | } | ||
76 | ✗ | else if (_outputType == OutputType::GnssObs) | |
77 | { | ||
78 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::GnssObs::type() }; | |
79 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::GnssObs::type(); | |
80 | } | ||
81 | |||
82 | ✗ | for (auto& link : outputPins.front().links) | |
83 | { | ||
84 | ✗ | if (auto* connectedPin = link.getConnectedPin()) | |
85 | { | ||
86 | ✗ | outputPins.front().recreateLink(*connectedPin); | |
87 | } | ||
88 | } | ||
89 | |||
90 | ✗ | flow::ApplyChanges(); | |
91 | } | ||
92 | ✗ | if (_outputType == OutputType::ImuObsWDelta || _outputType == OutputType::ImuObs) | |
93 | { | ||
94 | ✗ | if (ImGui::Checkbox(fmt::format("Use compensated data##{}", size_t(id)).c_str(), &_useCompensatedData)) | |
95 | { | ||
96 | ✗ | LOG_DEBUG("{}: _useCompensatedData changed to {}", nameId(), _useCompensatedData); | |
97 | ✗ | flow::ApplyChanges(); | |
98 | } | ||
99 | } | ||
100 | ✗ | else if (_outputType == OutputType::PosVelAtt) | |
101 | { | ||
102 | ✗ | if (auto posVelSource = static_cast<int>(_posVelSource); | |
103 | ✗ | ImGui::Combo(fmt::format("Data Source##{}", size_t(id)).c_str(), &posVelSource, "Best\0INS\0GNSS 1\0GNSS 2\0\0")) | |
104 | { | ||
105 | ✗ | _posVelSource = static_cast<decltype(_posVelSource)>(posVelSource); | |
106 | ✗ | LOG_DEBUG("{}: _posVelSource changed to {}", nameId(), fmt::underlying(_posVelSource)); | |
107 | ✗ | flow::ApplyChanges(); | |
108 | } | ||
109 | ✗ | if (ImGui::Checkbox(fmt::format("Force static##{}", size_t(id)).c_str(), &_forceStatic)) | |
110 | { | ||
111 | ✗ | LOG_DEBUG("{}: _forceStatic changed to {}", nameId(), _forceStatic); | |
112 | ✗ | flow::ApplyChanges(); | |
113 | } | ||
114 | } | ||
115 | ✗ | } | |
116 | |||
117 | ✗ | [[nodiscard]] json NAV::VectorNavBinaryConverter::save() const | |
118 | { | ||
119 | LOG_TRACE("{}: called", nameId()); | ||
120 | |||
121 | ✗ | json j; | |
122 | |||
123 | ✗ | j["outputType"] = _outputType; | |
124 | ✗ | j["posVelSource"] = _posVelSource; | |
125 | ✗ | j["forceStatic"] = _forceStatic; | |
126 | ✗ | j["useCompensatedData"] = _useCompensatedData; | |
127 | |||
128 | ✗ | return j; | |
129 | ✗ | } | |
130 | |||
131 | 32 | void NAV::VectorNavBinaryConverter::restore(json const& j) | |
132 | { | ||
133 | LOG_TRACE("{}: called", nameId()); | ||
134 | |||
135 |
1/2✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
|
32 | if (j.contains("outputType")) |
136 | { | ||
137 | 32 | j.at("outputType").get_to(_outputType); | |
138 | |||
139 |
1/2✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
|
32 | if (!outputPins.empty()) |
140 | { | ||
141 |
2/2✓ Branch 0 taken 16 times.
✓ Branch 1 taken 16 times.
|
32 | if (_outputType == OutputType::ImuObsWDelta) |
142 | { | ||
143 |
3/6✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 16 times.
✓ Branch 4 taken 16 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
32 | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::ImuObsWDelta::type() }; |
144 |
2/4✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16 times.
✗ Branch 5 not taken.
|
16 | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::ImuObsWDelta::type(); |
145 | } | ||
146 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 16 times.
|
16 | else if (_outputType == OutputType::ImuObs) |
147 | { | ||
148 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::ImuObs::type() }; | |
149 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::ImuObs::type(); | |
150 | } | ||
151 |
1/2✓ Branch 0 taken 16 times.
✗ Branch 1 not taken.
|
16 | else if (_outputType == OutputType::PosVelAtt) |
152 | { | ||
153 |
3/6✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 16 times.
✓ Branch 4 taken 16 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
|
32 | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::PosVelAtt::type() }; |
154 |
2/4✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16 times.
✗ Branch 5 not taken.
|
16 | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::PosVelAtt::type(); |
155 | } | ||
156 | ✗ | else if (_outputType == OutputType::GnssObs) | |
157 | { | ||
158 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).dataIdentifier = { NAV::GnssObs::type() }; | |
159 | ✗ | outputPins.at(OUTPUT_PORT_INDEX_CONVERTED).name = NAV::GnssObs::type(); | |
160 | } | ||
161 | } | ||
162 | } | ||
163 |
1/2✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
|
32 | if (j.contains("posVelSource")) |
164 | { | ||
165 | 32 | j.at("posVelSource").get_to(_posVelSource); | |
166 | } | ||
167 |
1/2✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
|
32 | if (j.contains("forceStatic")) |
168 | { | ||
169 | 32 | _forceStatic = j.at("forceStatic"); | |
170 | } | ||
171 |
1/2✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
|
32 | if (j.contains("useCompensatedData")) |
172 | { | ||
173 | 32 | _useCompensatedData = j.at("useCompensatedData"); | |
174 | } | ||
175 | 64 | } | |
176 | |||
177 | 96 | bool NAV::VectorNavBinaryConverter::initialize() | |
178 | { | ||
179 | LOG_TRACE("{}: called", nameId()); | ||
180 | |||
181 | 96 | _posVelAtt__init = nullptr; | |
182 | |||
183 | 96 | return true; | |
184 | } | ||
185 | |||
186 | 28384 | void NAV::VectorNavBinaryConverter::receiveObs(NAV::InputPin::NodeDataQueue& queue, size_t /* pinIdx */) | |
187 | { | ||
188 |
1/2✓ Branch 1 taken 28384 times.
✗ Branch 2 not taken.
|
28384 | auto vnObs = std::static_pointer_cast<const VectorNavBinaryOutput>(queue.extract_front()); |
189 | |||
190 | 28384 | std::shared_ptr<const NodeData> convertedData = nullptr; | |
191 | |||
192 |
2/2✓ Branch 0 taken 25776 times.
✓ Branch 1 taken 2608 times.
|
28384 | if (_outputType == OutputType::ImuObsWDelta) |
193 | { | ||
194 |
1/2✓ Branch 1 taken 25776 times.
✗ Branch 2 not taken.
|
25776 | convertedData = convert2ImuObsWDelta(vnObs); |
195 | } | ||
196 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 2608 times.
|
2608 | else if (_outputType == OutputType::ImuObs) |
197 | { | ||
198 | ✗ | convertedData = convert2ImuObs(vnObs); | |
199 | } | ||
200 |
1/2✓ Branch 0 taken 2608 times.
✗ Branch 1 not taken.
|
2608 | else if (_outputType == OutputType::PosVelAtt) |
201 | { | ||
202 |
1/2✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
|
2608 | convertedData = convert2PosVelAtt(vnObs); |
203 | } | ||
204 | ✗ | else if (_outputType == OutputType::GnssObs) | |
205 | { | ||
206 | ✗ | convertedData = convert2GnssObs(vnObs); | |
207 | } | ||
208 | |||
209 |
1/2✓ Branch 1 taken 28384 times.
✗ Branch 2 not taken.
|
28384 | if (convertedData) |
210 | { | ||
211 |
1/2✓ Branch 1 taken 28384 times.
✗ Branch 2 not taken.
|
28384 | invokeCallbacks(OUTPUT_PORT_INDEX_CONVERTED, convertedData); |
212 | } | ||
213 | 28384 | } | |
214 | |||
215 | 25776 | std::shared_ptr<const NAV::ImuObsWDelta> NAV::VectorNavBinaryConverter::convert2ImuObsWDelta(const std::shared_ptr<const VectorNavBinaryOutput>& vnObs) const // NOLINT(readability-convert-member-functions-to-static) | |
216 | { | ||
217 |
1/2✓ Branch 2 taken 25776 times.
✗ Branch 3 not taken.
|
25776 | auto imuObs = std::make_shared<ImuObsWDelta>(vnObs->imuPos); |
218 | |||
219 |
2/6✗ Branch 2 not taken.
✓ Branch 3 taken 25776 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✓ Branch 8 taken 25776 times.
✗ Branch 9 not taken.
|
25776 | if (vnObs->gnss1Outputs || vnObs->gnss2Outputs) // If there is no GNSS data selected in the vnSensor, Imu messages should still be sent out. The VN-100 will not provide any data otherwise. |
220 | { | ||
221 | 25776 | if (!vnObs->timeOutputs | |
222 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) |
223 |
1/2✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
|
25776 | || !vnObs->timeOutputs->timeStatus.dateOk() |
224 |
1/2✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
|
25776 | || !vnObs->timeOutputs->timeStatus.timeOk() |
225 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW) |
226 |
4/8✓ Branch 0 taken 25776 times.
✗ Branch 1 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✓ Branch 8 taken 25776 times.
✗ Branch 9 not taken.
✓ Branch 10 taken 25776 times.
|
51552 | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)) |
227 | { | ||
228 | ✗ | return nullptr; | |
229 | } | ||
230 |
1/2✓ Branch 7 taken 25776 times.
✗ Branch 8 not taken.
|
25776 | imuObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->timeOutputs->gpsWeek), static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L)); |
231 | } | ||
232 | else | ||
233 | { | ||
234 | // VN-100 vnObs->insTime is set from | ||
235 | // - 'timeSyncMaster->ppsTime + timeSyncIn' when working together with the VN-310E or | ||
236 | // - the computer time | ||
237 | ✗ | imuObs->insTime = vnObs->insTime; | |
238 | } | ||
239 | |||
240 |
1/2✓ Branch 2 taken 25776 times.
✗ Branch 3 not taken.
|
25776 | if (vnObs->timeOutputs) |
241 | { | ||
242 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) |
243 | { | ||
244 | 25776 | imuObs->timeSinceStartup = vnObs->timeOutputs->timeStartup; | |
245 | } | ||
246 | } | ||
247 | 25776 | bool accelFound = false; | |
248 | 25776 | bool gyroFound = false; | |
249 | 25776 | bool dThetaFound = false; | |
250 | 25776 | bool dVelFound = false; | |
251 |
1/2✓ Branch 2 taken 25776 times.
✗ Branch 3 not taken.
|
25776 | if (vnObs->imuOutputs) |
252 | { | ||
253 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 25776 times.
|
25776 | if (!_useCompensatedData) |
254 | { | ||
255 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG) | |
256 | { | ||
257 | ✗ | imuObs->p_magneticField = vnObs->imuOutputs->uncompMag.cast<double>(); | |
258 | } | ||
259 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL) | |
260 | { | ||
261 | ✗ | imuObs->p_acceleration = vnObs->imuOutputs->uncompAccel.cast<double>(); | |
262 | ✗ | accelFound = true; | |
263 | } | ||
264 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO) | |
265 | { | ||
266 | ✗ | imuObs->p_angularRate = vnObs->imuOutputs->uncompGyro.cast<double>(); | |
267 | ✗ | gyroFound = true; | |
268 | } | ||
269 | } | ||
270 | else | ||
271 | { | ||
272 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG) |
273 | { | ||
274 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 25776 times.
✗ Branch 8 not taken.
|
25776 | imuObs->p_magneticField = vnObs->imuOutputs->mag.cast<double>(); |
275 | } | ||
276 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL) |
277 | { | ||
278 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 25776 times.
✗ Branch 8 not taken.
|
25776 | imuObs->p_acceleration = vnObs->imuOutputs->accel.cast<double>(); |
279 | 25776 | accelFound = true; | |
280 | } | ||
281 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE) |
282 | { | ||
283 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 25776 times.
✗ Branch 8 not taken.
|
25776 | imuObs->p_angularRate = vnObs->imuOutputs->angularRate.cast<double>(); |
284 | 25776 | gyroFound = true; | |
285 | } | ||
286 | } | ||
287 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP) |
288 | { | ||
289 | 25776 | imuObs->temperature = vnObs->imuOutputs->temp; | |
290 | } | ||
291 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA) |
292 | { | ||
293 | 25776 | imuObs->dtime = vnObs->imuOutputs->deltaTime; | |
294 |
3/6✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 25776 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 25776 times.
✗ Branch 11 not taken.
|
25776 | imuObs->dtheta = deg2rad(vnObs->imuOutputs->deltaTheta.cast<double>()); |
295 | 25776 | dThetaFound = true; | |
296 | } | ||
297 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 25776 times.
✗ Branch 6 not taken.
|
25776 | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL) |
298 | { | ||
299 |
2/4✓ Branch 3 taken 25776 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 25776 times.
✗ Branch 8 not taken.
|
25776 | imuObs->dvel = vnObs->imuOutputs->deltaV.cast<double>(); |
300 | 25776 | dVelFound = true; | |
301 | } | ||
302 | } | ||
303 | |||
304 |
4/8✓ Branch 0 taken 25776 times.
✗ Branch 1 not taken.
✓ Branch 2 taken 25776 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 25776 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 25776 times.
✗ Branch 7 not taken.
|
25776 | if (accelFound && gyroFound && dThetaFound && dVelFound) |
305 | { | ||
306 | 25776 | return imuObs; | |
307 | } | ||
308 | |||
309 | ✗ | LOG_ERROR("{}: Conversion failed. Need {} acceleration and gyroscope measurements and deltaTheta and deltaVel in the input data.", | |
310 | nameId(), _useCompensatedData ? "compensated" : "uncompensated"); | ||
311 | ✗ | return nullptr; | |
312 | 25776 | } | |
313 | |||
314 | ✗ | std::shared_ptr<const NAV::ImuObs> NAV::VectorNavBinaryConverter::convert2ImuObs(const std::shared_ptr<const VectorNavBinaryOutput>& vnObs) const // NOLINT(readability-convert-member-functions-to-static) | |
315 | { | ||
316 | ✗ | auto imuObs = std::make_shared<ImuObs>(vnObs->imuPos); | |
317 | |||
318 | ✗ | if (vnObs->gnss1Outputs || vnObs->gnss2Outputs) // If there is no GNSS data selected in the vnSensor, Imu messages should still be sent out. The VN-100 will not provide any data otherwise. | |
319 | { | ||
320 | ✗ | if (!vnObs->timeOutputs | |
321 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) | |
322 | ✗ | || !vnObs->timeOutputs->timeStatus.dateOk() | |
323 | ✗ | || !vnObs->timeOutputs->timeStatus.timeOk() | |
324 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW) | |
325 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)) | |
326 | { | ||
327 | ✗ | return nullptr; | |
328 | } | ||
329 | ✗ | imuObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->timeOutputs->gpsWeek), static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L)); | |
330 | } | ||
331 | else | ||
332 | { | ||
333 | // VN-100 vnObs->insTime is set from | ||
334 | // - 'timeSyncMaster->ppsTime + timeSyncIn' when working together with the VN-310E or | ||
335 | // - the computer time | ||
336 | ✗ | imuObs->insTime = vnObs->insTime; | |
337 | } | ||
338 | |||
339 | ✗ | if (vnObs->timeOutputs) | |
340 | { | ||
341 | ✗ | if (vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) | |
342 | { | ||
343 | ✗ | imuObs->timeSinceStartup = vnObs->timeOutputs->timeStartup; | |
344 | } | ||
345 | } | ||
346 | ✗ | bool accelFound = false; | |
347 | ✗ | bool gyroFound = false; | |
348 | ✗ | if (vnObs->imuOutputs) | |
349 | { | ||
350 | ✗ | if (!_useCompensatedData) | |
351 | { | ||
352 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG) | |
353 | { | ||
354 | ✗ | imuObs->p_magneticField = vnObs->imuOutputs->uncompMag.cast<double>(); | |
355 | } | ||
356 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL) | |
357 | { | ||
358 | ✗ | imuObs->p_acceleration = vnObs->imuOutputs->uncompAccel.cast<double>(); | |
359 | ✗ | accelFound = true; | |
360 | } | ||
361 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO) | |
362 | { | ||
363 | ✗ | imuObs->p_angularRate = vnObs->imuOutputs->uncompGyro.cast<double>(); | |
364 | ✗ | gyroFound = true; | |
365 | } | ||
366 | } | ||
367 | else | ||
368 | { | ||
369 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG) | |
370 | { | ||
371 | ✗ | imuObs->p_magneticField = vnObs->imuOutputs->mag.cast<double>(); | |
372 | } | ||
373 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL) | |
374 | { | ||
375 | ✗ | imuObs->p_acceleration = vnObs->imuOutputs->accel.cast<double>(); | |
376 | ✗ | accelFound = true; | |
377 | } | ||
378 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE) | |
379 | { | ||
380 | ✗ | imuObs->p_angularRate = vnObs->imuOutputs->angularRate.cast<double>(); | |
381 | ✗ | gyroFound = true; | |
382 | } | ||
383 | } | ||
384 | ✗ | if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP) | |
385 | { | ||
386 | ✗ | imuObs->temperature = vnObs->imuOutputs->temp; | |
387 | } | ||
388 | } | ||
389 | |||
390 | ✗ | if (accelFound && gyroFound) | |
391 | { | ||
392 | ✗ | return imuObs; | |
393 | } | ||
394 | |||
395 | ✗ | LOG_ERROR("{}: Conversion failed. Need {} acceleration and gyroscope measurements in the input data.", nameId(), _useCompensatedData ? "compensated" : "uncompensated"); | |
396 | ✗ | return nullptr; | |
397 | ✗ | } | |
398 | |||
399 | 2608 | std::shared_ptr<const NAV::PosVelAtt> NAV::VectorNavBinaryConverter::convert2PosVelAtt(const std::shared_ptr<const VectorNavBinaryOutput>& vnObs) // NOLINT(readability-convert-member-functions-to-static) | |
400 | { | ||
401 | 2608 | std::optional<Eigen::Quaterniond> n_Quat_b; | |
402 | 2608 | std::optional<Eigen::Vector3d> e_position; | |
403 | 2608 | std::optional<Eigen::Vector3d> lla_position; | |
404 | 2608 | std::optional<Eigen::Vector3d> n_velocity; | |
405 | |||
406 |
1/2✓ Branch 2 taken 2608 times.
✗ Branch 3 not taken.
|
2608 | if (vnObs->attitudeOutputs) |
407 | { | ||
408 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✗ Branch 5 not taken.
✓ Branch 6 taken 2608 times.
|
2608 | if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION) |
409 | { | ||
410 | ✗ | n_Quat_b = vnObs->attitudeOutputs->qtn.cast<double>(); | |
411 | } | ||
412 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | else if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL) |
413 | { | ||
414 |
3/6✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2608 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2608 times.
✗ Branch 10 not taken.
|
2608 | Eigen::Vector3d ypr = deg2rad(vnObs->attitudeOutputs->ypr.cast<double>()); |
415 |
4/8✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2608 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2608 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2608 times.
✗ Branch 11 not taken.
|
2608 | n_Quat_b = trafo::n_Quat_b(ypr(2), ypr(1), ypr(0)); |
416 | } | ||
417 | ✗ | else if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM) | |
418 | { | ||
419 | ✗ | n_Quat_b = vnObs->attitudeOutputs->dcm.cast<double>(); | |
420 | } | ||
421 | } | ||
422 | |||
423 |
1/2✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
|
2608 | auto posVelAttObs = std::make_shared<PosVelAtt>(); |
424 | |||
425 | ✗ | if ((_posVelSource == PosVelSource_Best || _posVelSource == PosVelSource_Ins) | |
426 |
1/2✓ Branch 2 taken 2608 times.
✗ Branch 3 not taken.
|
2608 | && vnObs->insOutputs |
427 |
3/6✗ Branch 0 not taken.
✓ Branch 1 taken 2608 times.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
✗ Branch 7 not taken.
✓ Branch 8 taken 2608 times.
|
7824 | && (vnObs->insOutputs->insStatus.mode() == NAV::vendor::vectornav::InsStatus::Mode::Aligning |
428 |
1/2✗ Branch 3 not taken.
✓ Branch 4 taken 2608 times.
|
2608 | || vnObs->insOutputs->insStatus.mode() == NAV::vendor::vectornav::InsStatus::Mode::Tracking)) |
429 | { | ||
430 | ✗ | if (!vnObs->timeOutputs | |
431 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) | |
432 | ✗ | || !vnObs->timeOutputs->timeStatus.dateOk() | |
433 | ✗ | || !vnObs->timeOutputs->timeStatus.timeOk() | |
434 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW) | |
435 | ✗ | || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)) | |
436 | { | ||
437 | ✗ | return nullptr; | |
438 | } | ||
439 | |||
440 | ✗ | posVelAttObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->timeOutputs->gpsWeek), static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L)); | |
441 | |||
442 | ✗ | if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA) | |
443 | { | ||
444 | ✗ | lla_position = { deg2rad(vnObs->insOutputs->posLla(0)), | |
445 | ✗ | deg2rad(vnObs->insOutputs->posLla(1)), | |
446 | ✗ | vnObs->insOutputs->posLla(2) }; | |
447 | } | ||
448 | ✗ | if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF) | |
449 | { | ||
450 | ✗ | e_position = vnObs->insOutputs->posEcef; | |
451 | } | ||
452 | |||
453 | ✗ | if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED) | |
454 | { | ||
455 | ✗ | n_velocity = vnObs->insOutputs->velNed.cast<double>(); | |
456 | } | ||
457 | ✗ | else if ((vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF) | |
458 | ✗ | && (e_position.has_value() || lla_position.has_value())) | |
459 | { | ||
460 | ✗ | Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() : trafo::ecef2lla_WGS84(e_position.value()); | |
461 | ✗ | n_velocity = trafo::n_Quat_e(lla(0), lla(1)) * vnObs->insOutputs->velEcef.cast<double>(); | |
462 | } | ||
463 | ✗ | else if ((vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY) | |
464 | ✗ | && n_Quat_b.has_value()) | |
465 | { | ||
466 | ✗ | n_velocity = n_Quat_b.value() * vnObs->insOutputs->velBody.cast<double>(); | |
467 | } | ||
468 | } | ||
469 | |||
470 | ✗ | if ((_posVelSource == PosVelSource_Best || _posVelSource == PosVelSource_Gnss1) | |
471 |
4/8✗ Branch 0 not taken.
✓ Branch 1 taken 2608 times.
✓ Branch 4 taken 2608 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 2608 times.
✗ Branch 9 not taken.
✓ Branch 10 taken 2608 times.
✗ Branch 11 not taken.
|
2608 | && vnObs->gnss1Outputs && vnObs->gnss1Outputs->fix >= 2) |
472 | { | ||
473 | 2608 | if (!vnObs->gnss1Outputs | |
474 |
1/2✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
|
2608 | || !vnObs->gnss1Outputs->timeInfo.status.timeOk() |
475 |
3/6✓ Branch 0 taken 2608 times.
✗ Branch 1 not taken.
✗ Branch 5 not taken.
✓ Branch 6 taken 2608 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 2608 times.
|
5216 | || !vnObs->gnss1Outputs->timeInfo.status.dateOk()) |
476 | { | ||
477 | ✗ | return nullptr; | |
478 | } | ||
479 | |||
480 |
1/2✓ Branch 7 taken 2608 times.
✗ Branch 8 not taken.
|
2608 | posVelAttObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->gnss1Outputs->week), static_cast<double>(vnObs->gnss1Outputs->tow) * 1e-9L)); |
481 | |||
482 |
3/6✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2608 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 2608 times.
✗ Branch 7 not taken.
|
2608 | if (!e_position.has_value() && !lla_position.has_value()) |
483 | { | ||
484 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA) |
485 | { | ||
486 |
1/2✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
|
2608 | lla_position = { deg2rad(vnObs->gnss1Outputs->posLla(0)), |
487 |
1/2✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
|
2608 | deg2rad(vnObs->gnss1Outputs->posLla(1)), |
488 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2608 times.
✗ Branch 7 not taken.
|
2608 | vnObs->gnss1Outputs->posLla(2) }; |
489 | } | ||
490 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✗ Branch 5 not taken.
✓ Branch 6 taken 2608 times.
|
2608 | if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF) |
491 | { | ||
492 | ✗ | e_position = vnObs->gnss1Outputs->posEcef; | |
493 | } | ||
494 | } | ||
495 | |||
496 |
1/2✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
|
2608 | if (!n_velocity.has_value()) |
497 | { | ||
498 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED) |
499 | { | ||
500 |
2/4✓ Branch 3 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2608 times.
✗ Branch 7 not taken.
|
2608 | n_velocity = vnObs->gnss1Outputs->velNed.cast<double>(); |
501 | } | ||
502 | ✗ | else if ((vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF) | |
503 | ✗ | && (e_position.has_value() || lla_position.has_value())) | |
504 | { | ||
505 | ✗ | Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() : trafo::ecef2lla_WGS84(e_position.value()); | |
506 | ✗ | n_velocity = trafo::n_Quat_e(lla(0), lla(1)) * vnObs->gnss1Outputs->velEcef.cast<double>(); | |
507 | } | ||
508 | } | ||
509 | } | ||
510 | ✗ | if ((_posVelSource == PosVelSource_Best || _posVelSource == PosVelSource_Gnss2) | |
511 |
3/8✗ Branch 0 not taken.
✓ Branch 1 taken 2608 times.
✗ Branch 4 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 8 not taken.
✗ Branch 9 not taken.
✗ Branch 10 not taken.
✓ Branch 11 taken 2608 times.
|
2608 | && vnObs->gnss2Outputs && vnObs->gnss2Outputs->fix >= 2) |
512 | { | ||
513 | ✗ | if (!vnObs->gnss2Outputs | |
514 | ✗ | || !vnObs->gnss2Outputs->timeInfo.status.timeOk() | |
515 | ✗ | || !vnObs->gnss2Outputs->timeInfo.status.dateOk()) | |
516 | { | ||
517 | ✗ | return nullptr; | |
518 | } | ||
519 | |||
520 | ✗ | posVelAttObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->gnss2Outputs->week), static_cast<double>(vnObs->gnss2Outputs->tow) * 1e-9L)); | |
521 | |||
522 | ✗ | if (!e_position.has_value() && !lla_position.has_value()) | |
523 | { | ||
524 | ✗ | if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA) | |
525 | { | ||
526 | ✗ | lla_position = { deg2rad(vnObs->gnss2Outputs->posLla(0)), | |
527 | ✗ | deg2rad(vnObs->gnss2Outputs->posLla(1)), | |
528 | ✗ | vnObs->gnss2Outputs->posLla(2) }; | |
529 | } | ||
530 | ✗ | if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF) | |
531 | { | ||
532 | ✗ | e_position = vnObs->gnss2Outputs->posEcef; | |
533 | } | ||
534 | } | ||
535 | |||
536 | ✗ | if (!n_velocity.has_value()) | |
537 | { | ||
538 | ✗ | if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED) | |
539 | { | ||
540 | ✗ | n_velocity = vnObs->gnss2Outputs->velNed.cast<double>(); | |
541 | } | ||
542 | ✗ | else if ((vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF) | |
543 | ✗ | && (e_position.has_value() || lla_position.has_value())) | |
544 | { | ||
545 | ✗ | Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() : trafo::ecef2lla_WGS84(e_position.value()); | |
546 | ✗ | n_velocity = trafo::n_Quat_e(lla(0), lla(1)) * vnObs->gnss2Outputs->velEcef.cast<double>(); | |
547 | } | ||
548 | } | ||
549 | } | ||
550 | |||
551 |
4/8✓ Branch 1 taken 2608 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2608 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2608 times.
✗ Branch 8 not taken.
✓ Branch 9 taken 2608 times.
✗ Branch 10 not taken.
|
2608 | if ((e_position.has_value() || lla_position.has_value()) && n_velocity.has_value()) |
552 | { | ||
553 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 2608 times.
|
2608 | if (e_position.has_value()) |
554 | { | ||
555 | ✗ | posVelAttObs->setPosition_e(e_position.value()); | |
556 | } | ||
557 | else | ||
558 | { | ||
559 |
2/4✓ Branch 2 taken 2608 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | posVelAttObs->setPosition_lla(lla_position.value()); |
560 | } | ||
561 |
2/4✓ Branch 2 taken 2608 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | posVelAttObs->setVelocity_n(n_velocity.value()); |
562 | |||
563 |
1/2✗ Branch 1 not taken.
✓ Branch 2 taken 2608 times.
|
2608 | if (!n_Quat_b.has_value()) |
564 | { | ||
565 | ✗ | LOG_DEBUG("{}: Conversion succeeded but has no attitude info.", nameId()); | |
566 | } | ||
567 | else | ||
568 | { | ||
569 |
2/4✓ Branch 2 taken 2608 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2608 times.
✗ Branch 6 not taken.
|
2608 | posVelAttObs->setAttitude_n_Quat_b(n_Quat_b.value()); |
570 | } | ||
571 | |||
572 |
2/2✓ Branch 1 taken 16 times.
✓ Branch 2 taken 2592 times.
|
2608 | if (_posVelAtt__init == nullptr) |
573 | { | ||
574 | 16 | _posVelAtt__init = posVelAttObs; | |
575 | } | ||
576 | |||
577 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 2608 times.
|
2608 | if (_forceStatic) |
578 | { | ||
579 | ✗ | posVelAttObs->setPosition_e(_posVelAtt__init->e_position()); | |
580 | ✗ | posVelAttObs->setVelocity_n(Eigen::Vector3d::Zero()); | |
581 | ✗ | posVelAttObs->setAttitude_n_Quat_b(_posVelAtt__init->n_Quat_b()); | |
582 | } | ||
583 | |||
584 | 2608 | return posVelAttObs; | |
585 | } | ||
586 | |||
587 | ✗ | LOG_ERROR("{}: Conversion failed. No position or velocity data found in the input data.", nameId()); | |
588 | ✗ | return nullptr; | |
589 | 2608 | } | |
590 | |||
591 | ✗ | std::shared_ptr<const NAV::GnssObs> NAV::VectorNavBinaryConverter::convert2GnssObs(const std::shared_ptr<const VectorNavBinaryOutput>& vnObs) | |
592 | { | ||
593 | ✗ | auto gnssObs = std::make_shared<GnssObs>(); | |
594 | |||
595 | ✗ | if (!vnObs->gnss1Outputs | |
596 | ✗ | || !vnObs->gnss1Outputs->timeInfo.status.timeOk() | |
597 | ✗ | || !vnObs->gnss1Outputs->timeInfo.status.dateOk()) | |
598 | { | ||
599 | ✗ | return nullptr; | |
600 | } | ||
601 | |||
602 | ✗ | gnssObs->insTime = InsTime(InsTime_GPSweekTow(0, static_cast<int32_t>(vnObs->gnss1Outputs->raw.week), vnObs->gnss1Outputs->raw.tow)); | |
603 | |||
604 | ✗ | if (vnObs->gnss1Outputs) | |
605 | { | ||
606 | ✗ | if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS) | |
607 | { | ||
608 | ✗ | for (const auto& satRaw : vnObs->gnss1Outputs->raw.satellites) | |
609 | { | ||
610 | ✗ | bool skipMeasurement = false; | |
611 | ✗ | SatelliteSystem satSys = SatSys_None; | |
612 | ✗ | switch (satRaw.sys) | |
613 | { | ||
614 | ✗ | case vendor::vectornav::SatSys::GPS: | |
615 | ✗ | satSys = GPS; | |
616 | ✗ | break; | |
617 | ✗ | case vendor::vectornav::SatSys::SBAS: | |
618 | ✗ | satSys = SBAS; | |
619 | ✗ | break; | |
620 | ✗ | case vendor::vectornav::SatSys::Galileo: | |
621 | ✗ | satSys = GAL; | |
622 | ✗ | break; | |
623 | ✗ | case vendor::vectornav::SatSys::BeiDou: | |
624 | ✗ | satSys = BDS; | |
625 | ✗ | break; | |
626 | ✗ | case vendor::vectornav::SatSys::IMES: | |
627 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' is not supported yet. Skipping measurement.", satRaw.sys); | ||
628 | ✗ | skipMeasurement = true; | |
629 | ✗ | break; | |
630 | ✗ | case vendor::vectornav::SatSys::QZSS: | |
631 | ✗ | satSys = QZSS; | |
632 | ✗ | break; | |
633 | ✗ | case vendor::vectornav::SatSys::GLONASS: | |
634 | ✗ | satSys = GLO; | |
635 | ✗ | break; | |
636 | ✗ | default: // IRNSS not in vectorNav | |
637 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' is not supported yet. Skipping measurement.", satRaw.sys); | ||
638 | ✗ | skipMeasurement = true; | |
639 | ✗ | break; | |
640 | } | ||
641 | |||
642 | ✗ | Frequency frequency = Freq_None; | |
643 | ✗ | Code code; | |
644 | ✗ | switch (SatelliteSystem_(satSys)) | |
645 | { | ||
646 | ✗ | case GPS: | |
647 | ✗ | switch (satRaw.freq) | |
648 | { | ||
649 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
650 | ✗ | frequency = G01; | |
651 | ✗ | switch (satRaw.chan) | |
652 | { | ||
653 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::P_Code: | |
654 | ✗ | code = Code::G1P; | |
655 | ✗ | break; | |
656 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
657 | ✗ | code = Code::G1C; | |
658 | ✗ | break; | |
659 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Y_Code: | |
660 | ✗ | code = Code::G1Y; | |
661 | ✗ | break; | |
662 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Code: | |
663 | ✗ | code = Code::G1M; | |
664 | ✗ | break; | |
665 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Codeless: | |
666 | ✗ | code = Code::G1N; | |
667 | ✗ | break; | |
668 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Chan: | |
669 | ✗ | code = Code::G1S; | |
670 | ✗ | break; | |
671 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::L_Chan: | |
672 | ✗ | code = Code::G1L; | |
673 | ✗ | break; | |
674 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
675 | ✗ | code = Code::G1X; | |
676 | ✗ | break; | |
677 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Z_Tracking: | |
678 | ✗ | code = Code::G1W; | |
679 | ✗ | break; | |
680 | ✗ | default: | |
681 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
682 | ✗ | skipMeasurement = true; | |
683 | ✗ | break; | |
684 | } | ||
685 | ✗ | break; | |
686 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L2: | |
687 | ✗ | frequency = G02; | |
688 | ✗ | switch (satRaw.chan) | |
689 | { | ||
690 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::P_Code: | |
691 | ✗ | code = Code::G2P; | |
692 | ✗ | break; | |
693 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
694 | ✗ | code = Code::G2C; | |
695 | ✗ | break; | |
696 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::SemiCodeless: | |
697 | ✗ | code = Code::G2D; | |
698 | ✗ | break; | |
699 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Y_Code: | |
700 | ✗ | code = Code::G2Y; | |
701 | ✗ | break; | |
702 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Code: | |
703 | ✗ | code = Code::G2M; | |
704 | ✗ | break; | |
705 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Codeless: | |
706 | ✗ | code = Code::G2N; | |
707 | ✗ | break; | |
708 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Chan: | |
709 | ✗ | code = Code::G2S; | |
710 | ✗ | break; | |
711 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::L_Chan: | |
712 | ✗ | code = Code::G2L; | |
713 | ✗ | break; | |
714 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
715 | ✗ | code = Code::G2X; | |
716 | ✗ | break; | |
717 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Z_Tracking: | |
718 | ✗ | code = Code::G2W; | |
719 | ✗ | break; | |
720 | ✗ | default: | |
721 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
722 | ✗ | skipMeasurement = true; | |
723 | ✗ | break; | |
724 | } | ||
725 | ✗ | break; | |
726 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L5: | |
727 | ✗ | frequency = G05; | |
728 | ✗ | switch (satRaw.chan) | |
729 | { | ||
730 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
731 | ✗ | code = Code::G5I; | |
732 | ✗ | break; | |
733 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
734 | ✗ | code = Code::G5Q; | |
735 | ✗ | break; | |
736 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
737 | ✗ | code = Code::G5X; | |
738 | ✗ | break; | |
739 | ✗ | default: | |
740 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
741 | ✗ | skipMeasurement = true; | |
742 | ✗ | break; | |
743 | } | ||
744 | ✗ | break; | |
745 | ✗ | default: | |
746 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
747 | ✗ | skipMeasurement = true; | |
748 | ✗ | break; | |
749 | } | ||
750 | ✗ | break; | |
751 | ✗ | case SBAS: | |
752 | ✗ | switch (satRaw.freq) | |
753 | { | ||
754 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
755 | ✗ | frequency = S01; | |
756 | ✗ | switch (satRaw.chan) | |
757 | { | ||
758 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
759 | ✗ | code = Code::S1C; | |
760 | ✗ | break; | |
761 | ✗ | default: | |
762 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
763 | ✗ | skipMeasurement = true; | |
764 | ✗ | break; | |
765 | } | ||
766 | ✗ | break; | |
767 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L5: | |
768 | ✗ | frequency = S05; | |
769 | ✗ | switch (satRaw.chan) | |
770 | { | ||
771 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
772 | ✗ | code = Code::S5I; | |
773 | ✗ | break; | |
774 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
775 | ✗ | code = Code::S5Q; | |
776 | ✗ | break; | |
777 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
778 | ✗ | code = Code::S5X; | |
779 | ✗ | break; | |
780 | ✗ | default: | |
781 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
782 | ✗ | skipMeasurement = true; | |
783 | ✗ | break; | |
784 | } | ||
785 | ✗ | break; | |
786 | ✗ | default: | |
787 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
788 | ✗ | skipMeasurement = true; | |
789 | ✗ | break; | |
790 | } | ||
791 | ✗ | break; | |
792 | ✗ | case GAL: | |
793 | ✗ | switch (satRaw.freq) | |
794 | { | ||
795 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
796 | ✗ | frequency = E01; | |
797 | ✗ | switch (satRaw.chan) | |
798 | { | ||
799 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
800 | ✗ | code = Code::E1C; | |
801 | ✗ | break; | |
802 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::A_Chan: | |
803 | ✗ | code = Code::E1A; | |
804 | ✗ | break; | |
805 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::B_Chan: | |
806 | ✗ | code = Code::E1B; | |
807 | ✗ | break; | |
808 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
809 | ✗ | code = Code::E1X; | |
810 | ✗ | break; | |
811 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::ABC: | |
812 | ✗ | code = Code::E1Z; | |
813 | ✗ | break; | |
814 | ✗ | default: | |
815 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
816 | ✗ | skipMeasurement = true; | |
817 | ✗ | break; | |
818 | } | ||
819 | ✗ | break; | |
820 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L5: | |
821 | ✗ | frequency = E08; | |
822 | ✗ | switch (satRaw.chan) | |
823 | { | ||
824 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
825 | ✗ | code = Code::E8I; | |
826 | ✗ | break; | |
827 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
828 | ✗ | code = Code::E8Q; | |
829 | ✗ | break; | |
830 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
831 | ✗ | code = Code::E8X; | |
832 | ✗ | break; | |
833 | ✗ | default: | |
834 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
835 | ✗ | skipMeasurement = true; | |
836 | ✗ | break; | |
837 | } | ||
838 | ✗ | break; | |
839 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E6: | |
840 | ✗ | frequency = E06; | |
841 | ✗ | switch (satRaw.chan) | |
842 | { | ||
843 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::B_Chan: | |
844 | ✗ | code = Code::E6B; | |
845 | ✗ | break; | |
846 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
847 | ✗ | code = Code::E6C; | |
848 | ✗ | break; | |
849 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
850 | ✗ | code = Code::E6X; | |
851 | ✗ | break; | |
852 | ✗ | default: | |
853 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
854 | ✗ | skipMeasurement = true; | |
855 | ✗ | break; | |
856 | } | ||
857 | ✗ | break; | |
858 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E5a: | |
859 | ✗ | frequency = E05; | |
860 | ✗ | switch (satRaw.chan) | |
861 | { | ||
862 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
863 | ✗ | code = Code::E5I; | |
864 | ✗ | break; | |
865 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
866 | ✗ | code = Code::E5Q; | |
867 | ✗ | break; | |
868 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
869 | ✗ | code = Code::E5X; | |
870 | ✗ | break; | |
871 | ✗ | default: | |
872 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
873 | ✗ | skipMeasurement = true; | |
874 | ✗ | break; | |
875 | } | ||
876 | ✗ | break; | |
877 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E5b: | |
878 | ✗ | frequency = E07; | |
879 | ✗ | switch (satRaw.chan) | |
880 | { | ||
881 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
882 | ✗ | code = Code::E7I; | |
883 | ✗ | break; | |
884 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
885 | ✗ | code = Code::E7Q; | |
886 | ✗ | break; | |
887 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
888 | ✗ | code = Code::E7X; | |
889 | ✗ | break; | |
890 | ✗ | default: | |
891 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
892 | ✗ | skipMeasurement = true; | |
893 | ✗ | break; | |
894 | } | ||
895 | ✗ | break; | |
896 | ✗ | default: | |
897 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
898 | ✗ | skipMeasurement = true; | |
899 | ✗ | break; | |
900 | } | ||
901 | ✗ | break; | |
902 | ✗ | case BDS: | |
903 | ✗ | switch (satRaw.freq) | |
904 | { | ||
905 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
906 | ✗ | frequency = B01; | |
907 | ✗ | switch (satRaw.chan) | |
908 | { | ||
909 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
910 | ✗ | code = Code::B2I; | |
911 | ✗ | break; | |
912 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
913 | ✗ | code = Code::B2Q; | |
914 | ✗ | break; | |
915 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
916 | ✗ | code = Code::B2X; | |
917 | ✗ | break; | |
918 | ✗ | default: | |
919 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
920 | ✗ | skipMeasurement = true; | |
921 | ✗ | break; | |
922 | } | ||
923 | ✗ | break; | |
924 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E6: | |
925 | ✗ | frequency = B06; | |
926 | ✗ | switch (satRaw.chan) | |
927 | { | ||
928 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::A_Chan: | |
929 | ✗ | code = Code::B6A; | |
930 | ✗ | break; | |
931 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
932 | ✗ | code = Code::B6I; | |
933 | ✗ | break; | |
934 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
935 | ✗ | code = Code::B6Q; | |
936 | ✗ | break; | |
937 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
938 | ✗ | code = Code::B6X; | |
939 | ✗ | break; | |
940 | ✗ | default: | |
941 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
942 | ✗ | skipMeasurement = true; | |
943 | ✗ | break; | |
944 | } | ||
945 | ✗ | break; | |
946 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E5b: | |
947 | ✗ | frequency = B08; | |
948 | ✗ | switch (satRaw.chan) | |
949 | { | ||
950 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
951 | ✗ | code = Code::B7I; | |
952 | ✗ | break; | |
953 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
954 | ✗ | code = Code::B7Q; | |
955 | ✗ | break; | |
956 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
957 | ✗ | code = Code::B7X; | |
958 | ✗ | break; | |
959 | ✗ | default: | |
960 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
961 | ✗ | skipMeasurement = true; | |
962 | ✗ | break; | |
963 | } | ||
964 | ✗ | break; | |
965 | ✗ | default: | |
966 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
967 | ✗ | skipMeasurement = true; | |
968 | ✗ | break; | |
969 | } | ||
970 | ✗ | break; | |
971 | ✗ | case QZSS: | |
972 | ✗ | switch (satRaw.freq) | |
973 | { | ||
974 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
975 | ✗ | frequency = J01; | |
976 | ✗ | switch (satRaw.chan) | |
977 | { | ||
978 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
979 | ✗ | code = Code::J1C; | |
980 | ✗ | break; | |
981 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Chan: | |
982 | ✗ | code = Code::J1S; | |
983 | ✗ | break; | |
984 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::L_Chan: | |
985 | ✗ | code = Code::J1L; | |
986 | ✗ | break; | |
987 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
988 | ✗ | code = Code::J1X; | |
989 | ✗ | break; | |
990 | ✗ | default: | |
991 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
992 | ✗ | skipMeasurement = true; | |
993 | ✗ | break; | |
994 | } | ||
995 | ✗ | break; | |
996 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L2: | |
997 | ✗ | frequency = J02; | |
998 | ✗ | switch (satRaw.chan) | |
999 | { | ||
1000 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Chan: | |
1001 | ✗ | code = Code::J2S; | |
1002 | ✗ | break; | |
1003 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::L_Chan: | |
1004 | ✗ | code = Code::J2L; | |
1005 | ✗ | break; | |
1006 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
1007 | ✗ | code = Code::J2X; | |
1008 | ✗ | break; | |
1009 | ✗ | default: | |
1010 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
1011 | ✗ | skipMeasurement = true; | |
1012 | ✗ | break; | |
1013 | } | ||
1014 | ✗ | break; | |
1015 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L5: | |
1016 | ✗ | frequency = J05; | |
1017 | ✗ | switch (satRaw.chan) | |
1018 | { | ||
1019 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::I_Chan: | |
1020 | ✗ | code = Code::J5I; | |
1021 | ✗ | break; | |
1022 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::Q_Chan: | |
1023 | ✗ | code = Code::J5Q; | |
1024 | ✗ | break; | |
1025 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
1026 | ✗ | code = Code::J5X; | |
1027 | ✗ | break; | |
1028 | ✗ | default: | |
1029 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
1030 | ✗ | skipMeasurement = true; | |
1031 | ✗ | break; | |
1032 | } | ||
1033 | ✗ | break; | |
1034 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::E6: | |
1035 | ✗ | frequency = J06; | |
1036 | ✗ | switch (satRaw.chan) | |
1037 | { | ||
1038 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::M_Chan: | |
1039 | ✗ | code = Code::J6S; | |
1040 | ✗ | break; | |
1041 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::L_Chan: | |
1042 | ✗ | code = Code::J6L; | |
1043 | ✗ | break; | |
1044 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::BC_Chan: | |
1045 | ✗ | code = Code::J6X; | |
1046 | ✗ | break; | |
1047 | ✗ | default: | |
1048 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
1049 | ✗ | skipMeasurement = true; | |
1050 | ✗ | break; | |
1051 | } | ||
1052 | ✗ | break; | |
1053 | ✗ | default: | |
1054 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
1055 | ✗ | skipMeasurement = true; | |
1056 | ✗ | break; | |
1057 | } | ||
1058 | ✗ | break; | |
1059 | ✗ | case GLO: | |
1060 | ✗ | switch (satRaw.freq) | |
1061 | { | ||
1062 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L1: | |
1063 | ✗ | frequency = R01; | |
1064 | ✗ | switch (satRaw.chan) | |
1065 | { | ||
1066 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
1067 | ✗ | code = Code::R1C; | |
1068 | ✗ | break; | |
1069 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::P_Code: | |
1070 | ✗ | code = Code::R1P; | |
1071 | ✗ | break; | |
1072 | ✗ | default: | |
1073 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
1074 | ✗ | skipMeasurement = true; | |
1075 | ✗ | break; | |
1076 | } | ||
1077 | ✗ | break; | |
1078 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Freq::L2: | |
1079 | ✗ | frequency = R02; | |
1080 | ✗ | switch (satRaw.chan) | |
1081 | { | ||
1082 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::CA_Code: | |
1083 | ✗ | code = Code::R2C; | |
1084 | ✗ | break; | |
1085 | ✗ | case vendor::vectornav::RawMeas::SatRawElement::Chan::P_Code: | |
1086 | ✗ | code = Code::R2P; | |
1087 | ✗ | break; | |
1088 | ✗ | default: | |
1089 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan); | ||
1090 | ✗ | skipMeasurement = true; | |
1091 | ✗ | break; | |
1092 | } | ||
1093 | ✗ | break; | |
1094 | ✗ | default: | |
1095 | LOG_TRACE("VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq); | ||
1096 | ✗ | skipMeasurement = true; | |
1097 | ✗ | break; | |
1098 | } | ||
1099 | ✗ | break; | |
1100 | ✗ | case IRNSS: // IRNSS not in vectorNav | |
1101 | case SatSys_None: | ||
1102 | ✗ | skipMeasurement = true; | |
1103 | ✗ | break; | |
1104 | } | ||
1105 | |||
1106 | ✗ | if (skipMeasurement) | |
1107 | { | ||
1108 | ✗ | continue; | |
1109 | } | ||
1110 | |||
1111 | ✗ | (*gnssObs)(SatSigId(code, satRaw.svId)).pseudorange = { .value = satRaw.pr }; | |
1112 | ✗ | (*gnssObs)(SatSigId(code, satRaw.svId)).carrierPhase = { .value = satRaw.cp }; | |
1113 | ✗ | (*gnssObs)(SatSigId(code, satRaw.svId)).doppler = satRaw.dp; | |
1114 | ✗ | (*gnssObs)(SatSigId(code, satRaw.svId)).CN0 = satRaw.cno; | |
1115 | |||
1116 | // LLI has not been implemented yet, but can be calculated from vendor::vectornav::RawMeas::SatRawElement::Flags | ||
1117 | // (*gnssObs)[{ frequency, satRaw.svId }].LLI = ... | ||
1118 | } | ||
1119 | } | ||
1120 | } | ||
1121 | |||
1122 | ✗ | return gnssObs; | |
1123 | ✗ | } | |
1124 | |||
1125 | ✗ | const char* NAV::to_string(NAV::VectorNavBinaryConverter::OutputType value) | |
1126 | { | ||
1127 | ✗ | switch (value) | |
1128 | { | ||
1129 | ✗ | case NAV::VectorNavBinaryConverter::OutputType::ImuObs: | |
1130 | ✗ | return "ImuObs"; | |
1131 | ✗ | case NAV::VectorNavBinaryConverter::OutputType::ImuObsWDelta: | |
1132 | ✗ | return "ImuObsWDelta"; | |
1133 | ✗ | case NAV::VectorNavBinaryConverter::OutputType::PosVelAtt: | |
1134 | ✗ | return "PosVelAtt"; | |
1135 | ✗ | case NAV::VectorNavBinaryConverter::OutputType::GnssObs: | |
1136 | ✗ | return "GnssObs"; | |
1137 | ✗ | case NAV::VectorNavBinaryConverter::OutputType::COUNT: | |
1138 | ✗ | return ""; | |
1139 | } | ||
1140 | ✗ | return ""; | |
1141 | } | ||
1142 |