stdbin_decoder.test.cc
Go to the documentation of this file.
1 #include <gtest/gtest.h>
3 
8 
10 
11 TEST_F(TestStdBinDecoderErrorRecovery, RecoveryFromBadCheckSum){
12  // add bad frame to buffer
13  this->addNewDataFrame(BAD_CHECK_SUM);
14  this->testIsErrorIsThrown(0);
15 
16  this->testFramesErrorRecovery();
17 }
18 
19 TEST_F(TestStdBinDecoderErrorRecovery, RecoveryFromBadNavProtocolVersion){
20  // add bad frame to buffer
21  this->addNewDataFrame(BAD_NAV_PROTOCOL_VERSION);
22  ssize_t cleaned_buffer_size = BAD_NAV_PROTOCOL_VERSION.size() - 1;
23  this->testIsErrorIsThrown(cleaned_buffer_size);
24 
25  this->testFramesErrorRecovery();
26 }
27 
28 TEST_F(TestStdBinDecoderErrorRecovery, RecoveryFromBadAnswerProtocolVersion){
29  // add bad frame to buffer
30  this->addNewDataFrame(BAD_ANSWER_PROTOCOL_VERSION);
31  ssize_t cleaned_buffer_size = BAD_ANSWER_PROTOCOL_VERSION.size() - 1;
32  this->testIsErrorIsThrown(cleaned_buffer_size);
33 
34  this->testFramesErrorRecovery();
35 }
36 
37 TEST(StdBinDecoder, WeCannotParseAFrameWithSomeMissingFields)
38 {
39  // Given a frame with only attitude :
40  // clang-format off
41  const std::vector<uint8_t> memory{
42  'I', 'X', /*IX blue header */
43  0x02, /*Protocol Version */
44  0x00, 0x00, 0x00, 0x01, /* navigation bitmask (0x00000001 means only AttitudeAndHeading) */
45  0x00, 0x00, 0x00, 0x00, /* external data bitmask */
46  0x00, 0x21, /* Telegram size */
47  0x00, 0x00, 0x00, 0x05, /* navigation validity time (500 us) */
48  0x00, 0x00, 0x01, 0x23, /* counter (0x123) */
49  0x00, 0x00, 0xa0, 0x3f, /* Heading : 1.25f */
50  0x00, 0x00, 0xc0, 0xbf, /* roll : -1.5f */
51  0xcd, 0xcc, 0x48, 0x41, /* Pitch : 12.55f */
52  /* Checksum missing */
53  };
54  // clang-format on
55 
57  parser.addNewData(memory);
58  EXPECT_THROW(parser.parseNextFrame(), std::runtime_error);
59 }
60 
61 TEST(StdBinDecoder, WeCanParseAMinimalV2Frame)
62 {
63  // Given a frame with only attitude :
64  // clang-format off
65  const std::vector<uint8_t> memory{
66  'I', 'X', /*IX blue header */
67  0x02, /*Protocol Version */
68  0x00, 0x00, 0x00, 0x01, /* navigation bitmask (0x00000001 means only AttitudeAndHeading) */
69  0x00, 0x00, 0x00, 0x00, /* external data bitmask */
70  0x00, 0x25, /* Telegram size */
71  0x00, 0x00, 0x00, 0x05, /* navigation validity time (500 us) */
72  0x00, 0x00, 0x01, 0x23, /* counter (0x123) */
73  0x00, 0x00, 0xa0, 0x3f, /* Heading : 1.25f */
74  0x00, 0x00, 0xc0, 0xbf, /* roll : -1.5f */
75  0xcd, 0xcc, 0x48, 0x41, /* Pitch : 12.55f */
76  0x00, 0x00, 0x5, 0x72 /* Checksum */
77  };
78  // clang-format on
79 
81  parser.addNewData(memory);
82  ASSERT_TRUE(parser.parseNextFrame());
83  auto result = parser.getLastNavData();
84 
85  ASSERT_FALSE(result.attitudeHeadingDeviation.is_initialized());
86  ASSERT_TRUE(result.attitudeHeading.is_initialized());
87  // We don't test attitude heading is parsed with good values, we already have a test
88  // for this.
89 }
90 
91 TEST(StdBinDecoder, WeCanParseV2Protocol)
92 {
94 
95  parser.addNewData(log_STDBIN_V2);
96  ASSERT_TRUE(parser.parseNextFrame());
97  auto result = parser.getLastNavData();
98 
99  EXPECT_TRUE(result.attitudeHeading.is_initialized());
100  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 209.982);
101  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, 0.016);
102  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, 0.206);
103 
104  EXPECT_TRUE(result.attitudeHeadingDeviation.is_initialized());
105  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().heading_stdDev_deg, 2.4517534);
106  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().roll_stdDev_deg, 0.004243818);
107  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().pitch_stdDev_deg, 0.004769328);
108 
109  EXPECT_TRUE(result.rtHeaveSurgeSway.is_initialized());
110  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_withoutBdL, 0.0);
111  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_atBdL, 0.0);
112  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_surge_atBdL, 0.0);
113  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_sway_atBdL, 0.0);
114 
115  EXPECT_TRUE(result.smartHeave.is_initialized());
116  EXPECT_EQ(result.smartHeave.get().validityTime_100us, 9215311);
117  EXPECT_FLOAT_EQ(result.smartHeave.get().smartHeave_m, 0.0);
118 
119  EXPECT_TRUE(result.headingRollPitchRate.is_initialized());
120  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().heading_rate, 0.0);
121  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().roll_rate, 0.0);
122  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().pitch_rate, -0.002);
123 
124  EXPECT_TRUE(result.rotationRateVesselFrame.is_initialized());
125  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv1_degsec, 0.001287996);
126  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv2_degsec, 0.0010229985);
127  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv3_degsec, 0.0026694948);
128 
129  EXPECT_TRUE(result.accelerationVesselFrame.is_initialized());
130  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv1_msec2, -0.00034000012);
131  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv2_msec2, 0.000035000077);
132  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv3_msec2, 0.000055000033);
133 
134  EXPECT_TRUE(result.position.is_initialized());
135  EXPECT_DOUBLE_EQ(result.position.get().latitude_deg, 2.1332412116407853);
136  EXPECT_DOUBLE_EQ(result.position.get().longitude_deg, 48.000037178805215);
137  EXPECT_EQ(result.position.get().altitude_ref, 0);
138  EXPECT_FLOAT_EQ(result.position.get().altitude_m, 1.0547082);
139 
140  EXPECT_TRUE(result.positionDeviation.is_initialized());
141  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_stddev_m, 14.192304);
142  EXPECT_FLOAT_EQ(result.positionDeviation.get().east_stddev_m, 14.168153);
143  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_east_corr, 0.58203787);
144  EXPECT_FLOAT_EQ(result.positionDeviation.get().altitude_stddev_m, 7.6183596);
145 
146  EXPECT_TRUE(result.speedGeographicFrame.is_initialized());
147  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().north_msec, -0.0015761498);
148  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().east_msec, -0.027757198);
149  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().up_msec, 0.045121633);
150 
151  EXPECT_TRUE(result.speedGeographicFrameDeviation.is_initialized());
152  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().north_stddev_msec,
153  0.0114673115);
154  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().east_stddev_msec,
155  0.009463781);
156  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().up_stddev_msec,
157  0.029867083);
158 
159  EXPECT_TRUE(result.currentGeographicFrame.is_initialized());
160  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().north_msec, 0.0);
161  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().east_msec, -0.0);
162 
163  EXPECT_TRUE(result.currentGeographicFrameDeviation.is_initialized());
164  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().north_stddev_msec, 0.0);
165  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().east_stddev_msec, 0.0);
166 
167  EXPECT_TRUE(result.systemDate.is_initialized());
168  EXPECT_EQ(result.systemDate.get().day, 1);
169  EXPECT_EQ(result.systemDate.get().month, 1);
170  EXPECT_EQ(result.systemDate.get().year, 2006);
171 
172  EXPECT_TRUE(result.sensorStatus.is_initialized());
173  EXPECT_EQ(result.sensorStatus.get().status1, 0);
174  EXPECT_EQ(result.sensorStatus.get().status2, 0);
175 
176  EXPECT_TRUE(result.insAlgorithmStatus.is_initialized());
177  EXPECT_EQ(result.insAlgorithmStatus.get().status1, 0x12);
178  EXPECT_EQ(result.insAlgorithmStatus.get().status2, 0x30000);
179  EXPECT_EQ(result.insAlgorithmStatus.get().status3, 0x4000000);
180  EXPECT_EQ(result.insAlgorithmStatus.get().status4, 0x200);
181 
182  EXPECT_TRUE(result.insSystemStatus.is_initialized());
183  EXPECT_EQ(result.insSystemStatus.get().status1, 0x200);
184  EXPECT_EQ(result.insSystemStatus.get().status2, 0x1000);
185  EXPECT_EQ(result.insSystemStatus.get().status3, 0x0);
186 
187  EXPECT_TRUE(result.insUserStatus.is_initialized());
188  EXPECT_EQ(result.insUserStatus.get().status, 0x4c000000);
189 
190  EXPECT_FALSE(result.ahrsAlgorithmStatus.is_initialized());
191 
192  EXPECT_FALSE(result.ahrsSystemStatus.is_initialized());
193 
194  EXPECT_FALSE(result.ahrsUserStatus.is_initialized());
195 
196  EXPECT_TRUE(result.heaveSurgeSwaySpeed.is_initialized());
197  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().realtime_heave_speed, 0.0);
198  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().surge_speed, 0.0);
199  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().sway_speed, 0.0);
200 
201  EXPECT_TRUE(result.speedVesselFrame.is_initialized());
202  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv1_msec, 0.014972644);
203  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv2_msec, -0.023280365);
204  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv3_msec, 0.0449414);
205 
206  EXPECT_TRUE(result.accelerationGeographicFrame.is_initialized());
207  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().north_msec2, 0.0);
208  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().east_msec2, 0.0);
209  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().up_msec2, 9.809999);
210 
211  EXPECT_TRUE(result.courseSpeedoverGround.is_initialized());
212  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().course_over_ground, 266.96848);
213  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().speed_over_ground, 0.027778123);
214 
215  EXPECT_TRUE(result.temperatures.is_initialized());
216  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_fog, 26.158884);
217  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_acc, 26.158884);
218  EXPECT_FLOAT_EQ(result.temperatures.get().board_temperature, 158.65643);
219 
220  EXPECT_FALSE(result.attitudeQuaternion.is_initialized()); /* From V3 */
221 
222  EXPECT_FALSE(result.attitudeQuaternionDeviation.is_initialized()); /* From V3 */
223 
224  EXPECT_FALSE(result.rawAccelerationVesselFrame.is_initialized()); /* From V3 */
225 
226  EXPECT_FALSE(result.accelerationVesselFrameDeviation.is_initialized()); /* From V3 */
227 
228  EXPECT_FALSE(result.rotationRateVesselFrameDeviation.is_initialized()); /* From V3 */
229 }
230 
231 TEST(StdBinDecoder, WeCanParseV2ProtocolReceivedInTwoPartsWhereverCutpointIs)
232 {
233  // By instanciating parser out of the loop, we also test that we can parse
234  // multiple messages.
236 
237  for(size_t i = 1; i < log_STDBIN_V2.size(); ++i)
238  {
239  std::vector<uint8_t> part1, part2;
240  auto cutPoint = log_STDBIN_V2.begin();
241  // we cut the packet everywhere:
242  std::advance(cutPoint, i);
243  std::copy(std::begin(log_STDBIN_V2), cutPoint, std::back_inserter(part1));
244  std::copy(cutPoint, std::end(log_STDBIN_V2), std::back_inserter(part2));
245 
246  parser.addNewData(part1);
247  EXPECT_FALSE(parser.parseNextFrame());
248  parser.addNewData(part2);
249  ASSERT_TRUE(parser.parseNextFrame());
250  auto result = parser.getLastNavData();
251 
252  EXPECT_TRUE(result.attitudeHeading.is_initialized());
253  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 209.982);
254  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, 0.016);
255  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, 0.206);
256  }
257 }
258 
259 TEST(StdBinDecoder, WeCanParseV2ProtocolReceivedWithGarbageAtFront)
260 {
262 
263  std::vector<uint8_t> frame;
264  // First add half-frame (=garbage)
265  std::copy(log_STDBIN_V2.begin() + log_STDBIN_V2.size() / 2, log_STDBIN_V2.end(),
266  std::back_inserter(frame));
267  // Then complete frame
268  std::copy(log_STDBIN_V2.begin(), log_STDBIN_V2.end(), std::back_inserter(frame));
269 
270  parser.addNewData(frame);
271  ASSERT_TRUE(parser.parseNextFrame());
272  auto result = parser.getLastNavData();
273 
274  EXPECT_TRUE(result.attitudeHeading.is_initialized());
275  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 209.982);
276  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, 0.016);
277  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, 0.206);
278 }
279 
280 TEST(StdBinDecoder, WeCanParse2FramesInTheSameBufferWithGarbageOnFront)
281 {
283 
284  std::vector<uint8_t> frame;
285  // First add half-frame (=garbage)
286  std::copy(log_STDBIN_V2.begin() + log_STDBIN_V2.size() / 2, log_STDBIN_V2.end(),
287  std::back_inserter(frame));
288  // Then a V2 complete frame
289  std::copy(log_STDBIN_V2.begin(), log_STDBIN_V2.end(), std::back_inserter(frame));
290  // And a V4 complete frame
291  std::copy(log_STDBIN_V4.begin(), log_STDBIN_V4.end(), std::back_inserter(frame));
292 
293  parser.addNewData(frame);
294 
295  ASSERT_TRUE(parser.parseNextFrame());
296  const auto v2Header = parser.getLastHeaderData();
297  EXPECT_EQ(v2Header.protocolVersion, 2);
298 
299  ASSERT_TRUE(parser.parseNextFrame());
300  const auto v4Header = parser.getLastHeaderData();
301  EXPECT_EQ(v4Header.protocolVersion, 4);
302 
303  // Internal buffer is now empty, cannot parse a frame anymore
304  ASSERT_FALSE(parser.parseNextFrame());
305 }
306 
307 TEST(StdBinDecoder, WeCanParseV3Protocol)
308 {
310 
311  parser.addNewData(log_STDBIN_V3);
312  ASSERT_TRUE(parser.parseNextFrame());
313  auto result = parser.getLastNavData();
314 
315  // --- Navigation data block
316  EXPECT_TRUE(result.attitudeHeading.is_initialized());
317  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 0.0);
318  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, 0.809);
319  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, -0.521);
320 
321  EXPECT_TRUE(result.attitudeHeadingDeviation.is_initialized());
322  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().heading_stdDev_deg, 60.0);
323  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().roll_stdDev_deg, 4.9997573);
324  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().pitch_stdDev_deg, 4.999801);
325 
326  EXPECT_TRUE(result.rtHeaveSurgeSway.is_initialized());
327  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_withoutBdL, 0.0);
328  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_atBdL, 0.0);
329  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_surge_atBdL, 0.0);
330  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_sway_atBdL, 0.0);
331 
332  EXPECT_TRUE(result.smartHeave.is_initialized());
333  EXPECT_EQ(result.smartHeave.get().validityTime_100us, 565983535); // Sec
334  EXPECT_FLOAT_EQ(result.smartHeave.get().smartHeave_m, 0.0);
335 
336  EXPECT_TRUE(result.headingRollPitchRate.is_initialized());
337  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().heading_rate, 0.0);
338  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().roll_rate, 0.0);
339  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().pitch_rate, -0.0029999998);
340 
341  EXPECT_TRUE(result.rotationRateVesselFrame.is_initialized());
342  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv1_degsec, -0.0013599998);
343  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv2_degsec, -0.0021450005);
344  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv3_degsec, -0.000024999996);
345 
346  EXPECT_TRUE(result.accelerationVesselFrame.is_initialized());
347  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv1_msec2, -0.0004);
348  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv2_msec2, -0.00059999997);
349  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv3_msec2, -0.07685006);
350 
351  EXPECT_TRUE(result.position.is_initialized());
352  EXPECT_DOUBLE_EQ(result.position.get().latitude_deg, 48.899099791755994);
353  EXPECT_DOUBLE_EQ(result.position.get().longitude_deg, 2.061999802664471);
354  EXPECT_EQ(result.position.get().altitude_ref, 0);
355  EXPECT_FLOAT_EQ(result.position.get().altitude_m, 3004.5398);
356 
357  EXPECT_TRUE(result.positionDeviation.is_initialized());
358  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_stddev_m, 50.0);
359  EXPECT_FLOAT_EQ(result.positionDeviation.get().east_stddev_m, 50.0);
360  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_east_corr, -0.00005929864);
361  EXPECT_FLOAT_EQ(result.positionDeviation.get().altitude_stddev_m, 1.1056086);
362 
363  EXPECT_TRUE(result.speedGeographicFrame.is_initialized());
364  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().north_msec, -0.018215187);
365  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().east_msec, -0.012175002);
366  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().up_msec, 0.10336427);
367 
368  EXPECT_TRUE(result.speedGeographicFrameDeviation.is_initialized());
369  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().north_stddev_msec,
370  12.129728);
371  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().east_stddev_msec,
372  12.129744);
373  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().up_stddev_msec,
374  0.78773665);
375 
376  EXPECT_TRUE(result.currentGeographicFrame.is_initialized());
377  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().north_msec, 1.919778 * 1e-14);
378  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().east_msec, 4.5171327 * 1e-15);
379 
380  EXPECT_TRUE(result.currentGeographicFrameDeviation.is_initialized());
381  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().north_stddev_msec,
382  0.50110954);
383  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().east_stddev_msec,
384  0.5011094);
385 
386  EXPECT_TRUE(result.systemDate.is_initialized());
387  EXPECT_EQ(result.systemDate.get().day, 14);
388  EXPECT_EQ(result.systemDate.get().month, 3);
389  EXPECT_EQ(result.systemDate.get().year, 2019);
390 
391  EXPECT_TRUE(result.sensorStatus.is_initialized());
392  EXPECT_EQ(result.sensorStatus.get().status1, 0x0);
393  EXPECT_EQ(result.sensorStatus.get().status2, 0x100);
394 
395  EXPECT_TRUE(result.insAlgorithmStatus.is_initialized());
396  EXPECT_EQ(result.insAlgorithmStatus.get().status1, 0x81013112);
397  EXPECT_EQ(result.insAlgorithmStatus.get().status2, 0x1003011);
398  EXPECT_EQ(result.insAlgorithmStatus.get().status3, 0x4000100);
399  EXPECT_EQ(result.insAlgorithmStatus.get().status4, 0x200);
400 
401  EXPECT_TRUE(result.insSystemStatus.is_initialized());
402  EXPECT_EQ(result.insSystemStatus.get().status1, 0x08011e00);
403  EXPECT_EQ(result.insSystemStatus.get().status2, 0x8eff);
404  EXPECT_EQ(result.insSystemStatus.get().status3, 0x0);
405 
406  EXPECT_TRUE(result.insUserStatus.is_initialized());
407  EXPECT_EQ(result.insUserStatus.get().status, 0x4c001102);
408 
409  EXPECT_FALSE(result.ahrsAlgorithmStatus.is_initialized());
410 
411  EXPECT_FALSE(result.ahrsSystemStatus.is_initialized());
412 
413  EXPECT_FALSE(result.ahrsUserStatus.is_initialized());
414 
415  EXPECT_TRUE(result.heaveSurgeSwaySpeed.is_initialized());
416  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().realtime_heave_speed, 0.0);
417  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().surge_speed, 0.0);
418  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().sway_speed, 0.0);
419 
420  EXPECT_TRUE(result.speedVesselFrame.is_initialized());
421  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv1_msec, -0.017242743);
422  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv2_msec, 0.013600622);
423  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv3_msec, 0.10299126);
424 
425  EXPECT_TRUE(result.accelerationGeographicFrame.is_initialized());
426  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().north_msec2, 0.0);
427  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().east_msec2, 0.0);
428  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().up_msec2, 9.83);
429 
430  EXPECT_TRUE(result.courseSpeedoverGround.is_initialized());
431  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().course_over_ground, 213.74023);
432  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().speed_over_ground, 0.021863433);
433 
434  EXPECT_TRUE(result.temperatures.is_initialized());
435  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_fog, 28.700487);
436  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_acc, 37.533264);
437  EXPECT_FLOAT_EQ(result.temperatures.get().board_temperature, 47.899994);
438 
439  EXPECT_TRUE(result.attitudeQuaternion.is_initialized());
440  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q0, 0.9999646544456482);
441  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q1, -0.00706720445305109);
442  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q2, 0.00454969797283411);
443  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q3, -0.00003185356399626471);
444 
445  EXPECT_TRUE(result.attitudeQuaternionDeviation.is_initialized());
446  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi1,
447  0.08726222813129425);
448  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi2,
449  0.08726298809051514);
450  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi3,
451  1.0471975803375244);
452 
453  EXPECT_TRUE(result.rawAccelerationVesselFrame.is_initialized());
454  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv1_msec2, 0.0);
455  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv2_msec2, 0.0);
456  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv3_msec2, 7.999994);
457 
458  EXPECT_TRUE(result.accelerationVesselFrameDeviation.is_initialized());
459  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv1_stddev_msec2,
460  16.82827);
461  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv2_stddev_msec2,
462  16.827307);
463  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv3_stddev_msec2,
464  1.1194783);
465 
466  EXPECT_TRUE(result.rotationRateVesselFrameDeviation.is_initialized());
467  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv1_stddev_degsec,
468  0.00008998095);
469  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv2_stddev_degsec,
470  0.0029352242);
471  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv3_stddev_degsec,
472  0.0032638267);
473 
474  // --- Extended navigation data block
475  EXPECT_TRUE(result.rotationAccelerationVesselFrame.is_initialized());
476  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv1_degsec2,
477  0.0003888396);
478  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv2_degsec2,
479  0.0017579537);
480  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv3_degsec2,
481  0.0013762031);
482 
483  EXPECT_TRUE(result.rotationAccelerationVesselFrameDeviation.is_initialized());
484  EXPECT_FLOAT_EQ(
485  result.rotationAccelerationVesselFrameDeviation.get().xv1_stddev_degsec2,
486  0.0000141353985);
487  EXPECT_FLOAT_EQ(
488  result.rotationAccelerationVesselFrameDeviation.get().xv2_stddev_degsec2,
489  0.000014134977);
490  EXPECT_FLOAT_EQ(
491  result.rotationAccelerationVesselFrameDeviation.get().xv3_stddev_degsec2,
492  0.000014134976);
493 
494  EXPECT_TRUE(result.rawRotationRateVesselFrame.is_initialized());
495  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv1_degsec, 0.0);
496  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv2_degsec, 0.0);
497  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv3_degsec, 0.0);
498 
499  EXPECT_FALSE(result.vehicleAttitudeHeading.is_initialized());
500 
501  EXPECT_FALSE(result.vehicleAttitudeHeadingDeviation.is_initialized());
502 
503  EXPECT_FALSE(result.vehiclePosition.is_initialized());
504 
505  EXPECT_FALSE(result.vehiclePositionDeviation.is_initialized());
506 
507  // --- External data block
508  EXPECT_TRUE(result.utc.is_initialized());
509  EXPECT_EQ(result.utc.get().validityTime_100us, 566980000); // sec
510  EXPECT_EQ(result.utc.get().source, 0);
511 
512  EXPECT_TRUE(result.gnss1.is_initialized());
513  EXPECT_EQ(result.gnss1.get().validityTime_100us, 566981130); // sec
514  EXPECT_EQ(result.gnss1.get().gnss_id, 0);
515  EXPECT_EQ(result.gnss1.get().gnss_quality, 4);
516  EXPECT_DOUBLE_EQ(result.gnss1.get().latitude_deg, 48.89909998575846);
517  EXPECT_DOUBLE_EQ(result.gnss1.get().longitude_deg, 2.062000000476837);
518  EXPECT_FLOAT_EQ(result.gnss1.get().altitude_m, 3004.5);
519  EXPECT_FLOAT_EQ(result.gnss1.get().latitude_stddev_m, 0.1);
520  EXPECT_FLOAT_EQ(result.gnss1.get().longitude_stddev_m, 0.1);
521  EXPECT_FLOAT_EQ(result.gnss1.get().altitude_stddev_m, 0.1);
522  EXPECT_FLOAT_EQ(result.gnss1.get().lat_lon_stddev_m2, 0.0);
523  EXPECT_FLOAT_EQ(result.gnss1.get().geoidal_separation_m, 0.0);
524 
525  EXPECT_TRUE(result.gnss2.is_initialized());
526  EXPECT_EQ(result.gnss2.get().validityTime_100us, 566981130); // Sec
527  EXPECT_EQ(result.gnss2.get().gnss_id, 1);
528  EXPECT_EQ(result.gnss2.get().gnss_quality, 4);
529  EXPECT_DOUBLE_EQ(result.gnss2.get().latitude_deg, 48.89909998575846);
530  EXPECT_DOUBLE_EQ(result.gnss2.get().longitude_deg, 2.062000000476837);
531  EXPECT_FLOAT_EQ(result.gnss2.get().altitude_m, 3004.5);
532  EXPECT_FLOAT_EQ(result.gnss2.get().latitude_stddev_m, 0.1);
533  EXPECT_FLOAT_EQ(result.gnss2.get().longitude_stddev_m, 0.2);
534  EXPECT_FLOAT_EQ(result.gnss2.get().altitude_stddev_m, 0.3);
535  EXPECT_FLOAT_EQ(result.gnss2.get().lat_lon_stddev_m2, -0.0);
536  EXPECT_FLOAT_EQ(result.gnss2.get().geoidal_separation_m, 0.0);
537 
538  EXPECT_FALSE(result.gnssManual.is_initialized());
539 
540  EXPECT_TRUE(result.emlog1.is_initialized());
541  EXPECT_EQ(result.emlog1.get().validityTime_100us, 566980110);
542  EXPECT_EQ(result.emlog1.get().emlog_id, 0);
543  EXPECT_FLOAT_EQ(result.emlog1.get().xv1_waterSpeed_ms, 60.0);
544  EXPECT_FLOAT_EQ(result.emlog1.get().xv1_speed_stddev_ms, 0.01);
545 
546  EXPECT_FALSE(result.emlog2.is_initialized());
547 
548  EXPECT_TRUE(result.usbl1.is_initialized());
549  EXPECT_EQ(result.usbl1.get().validityTime_100us, 566980558);
550  EXPECT_EQ(result.usbl1.get().usbl_id, 0);
551  std::array<uint8_t, 8> beacon_usbl1 = {
552  {'A', 'B', 'C', '\0', '\0', '\0', '\0', '\0'}}; // TODO : VERIF
553  EXPECT_EQ(result.usbl1.get().beacon_id, beacon_usbl1);
554  EXPECT_EQ(result.usbl1.get().latitude_deg, 48.9);
555  EXPECT_DOUBLE_EQ(result.usbl1.get().longitude_deg, 2.0639999985694883);
556  EXPECT_DOUBLE_EQ(result.usbl1.get().altitude_m, 0.0);
557  EXPECT_FLOAT_EQ(result.usbl1.get().north_stddev_m, 2.0);
558  EXPECT_FLOAT_EQ(result.usbl1.get().east_stddev_m, 2.0);
559  EXPECT_FLOAT_EQ(result.usbl1.get().lat_lon_cov_m2, 0.0);
560  EXPECT_FLOAT_EQ(result.usbl1.get().altitude_stddev_m, 2.0);
561 
562  EXPECT_TRUE(result.usbl2.is_initialized());
563  EXPECT_EQ(result.usbl2.get().validityTime_100us, 566980110);
564  EXPECT_EQ(result.usbl2.get().usbl_id, 1);
565  std::array<uint8_t, 8> beacon_usbl2 = {
566  {'D', 'E', 'F', '\0', '\0', '\0', '\0', '\0'}}; // TODO : VERIF
567  EXPECT_EQ(result.usbl2.get().beacon_id, beacon_usbl2);
568  EXPECT_EQ(result.usbl2.get().latitude_deg, -48.898);
569  EXPECT_DOUBLE_EQ(result.usbl2.get().longitude_deg, 289.5933);
570  EXPECT_DOUBLE_EQ(result.usbl2.get().altitude_m, 0.0);
571  EXPECT_FLOAT_EQ(result.usbl2.get().north_stddev_m, 10.0);
572  EXPECT_FLOAT_EQ(result.usbl2.get().east_stddev_m, 10.0);
573  EXPECT_FLOAT_EQ(result.usbl2.get().lat_lon_cov_m2, 0.0);
574  EXPECT_FLOAT_EQ(result.usbl2.get().altitude_stddev_m, 10.0);
575 
576  EXPECT_FALSE(result.usbl3.is_initialized());
577 
578  EXPECT_TRUE(result.depth.is_initialized());
579  EXPECT_EQ(result.depth.get().validityTime_100us, 566980110); // Sec
580  EXPECT_EQ(result.depth.get().depth_m, -102.0);
581  EXPECT_EQ(result.depth.get().depth_stddev_m, 100.0);
582 
583  EXPECT_TRUE(result.dvlGroundSpeed1.is_initialized());
584  EXPECT_EQ(result.dvlGroundSpeed1.get().validityTime_100us, 566980110);
585  EXPECT_EQ(result.dvlGroundSpeed1.get().dvl_id, 0);
586  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv1_groundspeed_ms, 39.0);
587  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv2_groundspeed_ms, 39.0);
588  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv3_groundspeed_ms, 39.0);
589  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().dvl_speedofsound_ms, 1400.0);
590  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().dvl_altitude_m, 20.0);
591  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv1_stddev_ms, 3.0);
592  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv2_stddev_ms, 3.0);
593  EXPECT_FLOAT_EQ(result.dvlGroundSpeed1.get().xv3_stddev_ms, 3.0);
594 
595  EXPECT_TRUE(result.dvlWaterSpeed1.is_initialized());
596  EXPECT_EQ(result.dvlWaterSpeed1.get().validityTime_100us, 566980110);
597  EXPECT_EQ(result.dvlWaterSpeed1.get().dvl_id, 0);
598  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv1_waterspeed_ms, 18.571428);
599  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv2_waterspeed_ms, 18.571428);
600  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv3_waterspeed_ms, 18.571428);
601  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().dvl_speedofsound_ms, 1400.0);
602  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv1_stddev_ms, 3.0);
603  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv2_stddev_ms, 3.0);
604  EXPECT_FLOAT_EQ(result.dvlWaterSpeed1.get().xv3_stddev_ms, 3.0);
605 
606  EXPECT_TRUE(result.soundVelocity.is_initialized());
607  // EXPECT_EQ(result.soundVelocity.get().validityTime_100us, 0);
608  EXPECT_EQ(result.soundVelocity.get().ext_speedofsound_ms, 1300.0);
609 
610  EXPECT_FALSE(result.dmi.is_initialized());
611 
612  EXPECT_TRUE(result.lbl1.is_initialized());
613  EXPECT_EQ(result.lbl1.get().validityTime_100us, 566980558);
614  EXPECT_EQ(result.lbl1.get().rfu, 0);
615  std::array<uint8_t, 8> beacon_lbl1 = {
616  {'0', '\0', '\0', '\0', '\0', '\0', '\0', '\x1'}}; // TODO : verif
617  EXPECT_EQ(result.lbl1.get().beacon_id, beacon_lbl1);
618  EXPECT_DOUBLE_EQ(result.lbl1.get().beacon_latitude_deg, -48.89800001780192);
619  EXPECT_DOUBLE_EQ(result.lbl1.get().beacon_longitude_deg, 289.5960000038147);
620  EXPECT_FLOAT_EQ(result.lbl1.get().beacon_altitude_m, 0.0);
621  EXPECT_FLOAT_EQ(result.lbl1.get().range_m, 238.0);
622  EXPECT_FLOAT_EQ(result.lbl1.get().range_stddev_m, 10.0);
623 
624  EXPECT_FALSE(result.lbl2.is_initialized());
625 
626  EXPECT_FALSE(result.lbl3.is_initialized());
627 
628  EXPECT_FALSE(result.lbl4.is_initialized());
629 
630  EXPECT_FALSE(result.eventMarkerA.is_initialized());
631 
632  EXPECT_FALSE(result.eventMarkerB.is_initialized());
633 
634  EXPECT_FALSE(result.eventMarkerC.is_initialized());
635 
636  EXPECT_FALSE(result.dvlGroundSpeed2.is_initialized());
637 
638  EXPECT_FALSE(result.dvlWaterSpeed2.is_initialized());
639 
640  EXPECT_FALSE(result.turretAngles.is_initialized());
641 
642  EXPECT_FALSE(result.vtg1.is_initialized());
643 
644  EXPECT_FALSE(result.vtg2.is_initialized());
645 
646  EXPECT_FALSE(result.logBook.is_initialized());
647 }
648 
649 TEST(StdBinDecoder, WeCanParseV4Protocol)
650 {
652 
653  parser.addNewData(log_STDBIN_V4);
654  ASSERT_TRUE(parser.parseNextFrame());
655  auto result = parser.getLastNavData();
656 
657  // --- Navigation data block
658  EXPECT_TRUE(result.attitudeHeading.is_initialized());
659  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 357.428);
660  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, -0.04);
661  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, 0.178);
662 
663  EXPECT_TRUE(result.attitudeHeadingDeviation.is_initialized());
664  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().heading_stdDev_deg, 54.47794);
665  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().roll_stdDev_deg, 0.010677356);
666  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().pitch_stdDev_deg, 0.016798064);
667 
668  EXPECT_TRUE(result.rtHeaveSurgeSway.is_initialized());
669  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_withoutBdL, 0.0);
670  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_atBdL, 0.0);
671  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_surge_atBdL, 0.0);
672  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_sway_atBdL, 0.0);
673 
674  EXPECT_TRUE(result.smartHeave.is_initialized());
675  EXPECT_EQ(result.smartHeave.get().validityTime_100us, 8715306); // Sec
676  EXPECT_FLOAT_EQ(result.smartHeave.get().smartHeave_m, 0.0);
677 
678  EXPECT_TRUE(result.headingRollPitchRate.is_initialized());
679  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().heading_rate, -0.002);
680  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().roll_rate, -0.005);
681  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().pitch_rate, 0.0);
682 
683  EXPECT_TRUE(result.rotationRateVesselFrame.is_initialized());
684  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv1_degsec, -0.0061404924);
685  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv2_degsec, -0.00091849366);
686  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv3_degsec, 0.0024884976);
687 
688  EXPECT_TRUE(result.accelerationVesselFrame.is_initialized());
689  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv1_msec2, 0.00004);
690  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv2_msec2, 0.00040999975);
691  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv3_msec2, 0.0007599999);
692 
693  EXPECT_TRUE(result.position.is_initialized());
694  EXPECT_DOUBLE_EQ(result.position.get().latitude_deg, 2.133332706885363);
695  EXPECT_DOUBLE_EQ(result.position.get().longitude_deg, 47.999999832595385);
696  EXPECT_EQ(result.position.get().altitude_ref, 0);
697  EXPECT_FLOAT_EQ(result.position.get().altitude_m, 0.15949036);
698 
699  EXPECT_TRUE(result.positionDeviation.is_initialized());
700  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_stddev_m, 14.204068);
701  EXPECT_FLOAT_EQ(result.positionDeviation.get().east_stddev_m, 14.156303);
702  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_east_corr, 0.03173876);
703  EXPECT_FLOAT_EQ(result.positionDeviation.get().altitude_stddev_m, 2.828566);
704 
705  EXPECT_TRUE(result.speedGeographicFrame.is_initialized());
706  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().north_msec, -0.0003105167);
707  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().east_msec, -0.011570915);
708  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().up_msec, 0.04521207);
709 
710  EXPECT_TRUE(result.speedGeographicFrameDeviation.is_initialized());
711  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().north_stddev_msec,
712  0.006963054);
713  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().east_stddev_msec,
714  0.0066441046);
715  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().up_stddev_msec,
716  0.009995009);
717 
718  EXPECT_TRUE(result.currentGeographicFrame.is_initialized());
719  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().north_msec, 1.919778 * 0.0);
720  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().east_msec, 4.5171327 * 0.0);
721 
722  EXPECT_TRUE(result.currentGeographicFrameDeviation.is_initialized());
723  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().north_stddev_msec, 0.0);
724  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().east_stddev_msec, 0.0);
725 
726  EXPECT_TRUE(result.systemDate.is_initialized());
727  EXPECT_EQ(result.systemDate.get().day, 1);
728  EXPECT_EQ(result.systemDate.get().month, 1);
729  EXPECT_EQ(result.systemDate.get().year, 2006);
730 
731  EXPECT_TRUE(result.sensorStatus.is_initialized());
732  EXPECT_EQ(result.sensorStatus.get().status1, 0x0);
733  EXPECT_EQ(result.sensorStatus.get().status2, 0x0);
734 
735  EXPECT_TRUE(result.insAlgorithmStatus.is_initialized());
736  EXPECT_EQ(result.insAlgorithmStatus.get().status1, 0x00000012);
737  EXPECT_EQ(result.insAlgorithmStatus.get().status2, 0x00030000);
738  EXPECT_EQ(result.insAlgorithmStatus.get().status3, 0x04000000);
739  EXPECT_EQ(result.insAlgorithmStatus.get().status4, 0x00000200);
740 
741  EXPECT_TRUE(result.insSystemStatus.is_initialized());
742  EXPECT_EQ(result.insSystemStatus.get().status1, 0x00000200);
743  EXPECT_EQ(result.insSystemStatus.get().status2, 0x00001000);
744  EXPECT_EQ(result.insSystemStatus.get().status3, 0x0);
745 
746  EXPECT_TRUE(result.insUserStatus.is_initialized());
747  EXPECT_EQ(result.insUserStatus.get().status, 0x4c000000);
748 
749  EXPECT_FALSE(result.ahrsAlgorithmStatus.is_initialized());
750 
751  EXPECT_FALSE(result.ahrsSystemStatus.is_initialized());
752 
753  EXPECT_FALSE(result.ahrsUserStatus.is_initialized());
754 
755  EXPECT_TRUE(result.heaveSurgeSwaySpeed.is_initialized());
756  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().realtime_heave_speed, 0.0);
757  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().surge_speed, 0.0);
758  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().sway_speed, 0.0);
759 
760  EXPECT_TRUE(result.speedVesselFrame.is_initialized());
761  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv1_msec, 0.000061522915);
762  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv2_msec, 0.011496336);
763  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv3_msec, 0.04489224);
764 
765  EXPECT_TRUE(result.accelerationGeographicFrame.is_initialized());
766  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().north_msec2, 0.0);
767  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().east_msec2, 0.0);
768  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().up_msec2, 9.809999);
769 
770  EXPECT_TRUE(result.courseSpeedoverGround.is_initialized());
771  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().course_over_ground, 268.42966);
772  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().speed_over_ground, 0.011529781);
773 
774  EXPECT_TRUE(result.temperatures.is_initialized());
775  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_fog, 25.993078);
776  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_acc, 25.993078);
777  EXPECT_FLOAT_EQ(result.temperatures.get().board_temperature, 158.65643);
778 
779  EXPECT_TRUE(result.attitudeQuaternion.is_initialized());
780  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q0, 0.9997469186782837);
781  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q1, 0.00038782256888225675);
782  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q2, -0.0015508179785683751);
783  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q3, -0.02244032360613346);
784 
785  EXPECT_TRUE(result.attitudeQuaternionDeviation.is_initialized());
786  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi1,
787  0.00018635205924510956);
788  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi2,
789  0.00029318343149498105);
790  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi3,
791  0.9508194327354431);
792 
793  EXPECT_TRUE(result.rawAccelerationVesselFrame.is_initialized());
794  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv1_msec2, 0.0);
795  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv2_msec2, 0.0);
796  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv3_msec2, 8.000145);
797 
798  EXPECT_TRUE(result.accelerationVesselFrameDeviation.is_initialized());
799  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv1_stddev_msec2,
800  0.009960833);
801  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv2_stddev_msec2,
802  0.009610326);
803  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv3_stddev_msec2,
804  0.01413504);
805 
806  EXPECT_TRUE(result.rotationRateVesselFrameDeviation.is_initialized());
807  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv1_stddev_degsec,
808  0.0005122008);
809  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv2_stddev_degsec,
810  0.004000983);
811  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv3_stddev_degsec,
812  0.00051041954);
813 
814  // --- Extended navigation data block
815  EXPECT_TRUE(result.rotationAccelerationVesselFrame.is_initialized());
816  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv1_degsec2,
817  0.000536854);
818  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv2_degsec2,
819  0.002185823);
820  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv3_degsec2,
821  -0.00046422562);
822 
823  EXPECT_TRUE(result.rotationAccelerationVesselFrameDeviation.is_initialized());
824  EXPECT_FLOAT_EQ(
825  result.rotationAccelerationVesselFrameDeviation.get().xv1_stddev_degsec2,
826  0.000706749);
827  EXPECT_FLOAT_EQ(
828  result.rotationAccelerationVesselFrameDeviation.get().xv2_stddev_degsec2,
829  0.0007067489);
830  EXPECT_FLOAT_EQ(
831  result.rotationAccelerationVesselFrameDeviation.get().xv3_stddev_degsec2,
832  0.000706749);
833 
834  EXPECT_TRUE(result.rawRotationRateVesselFrame.is_initialized());
835  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv1_degsec, 0.0);
836  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv2_degsec, 0.0);
837  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv3_degsec, 0.0);
838 
839  EXPECT_FALSE(result.vehicleAttitudeHeading.is_initialized());
840 
841  EXPECT_FALSE(result.vehicleAttitudeHeadingDeviation.is_initialized());
842 
843  EXPECT_FALSE(result.vehiclePosition.is_initialized());
844 
845  EXPECT_FALSE(result.vehiclePositionDeviation.is_initialized());
846 
847  // --- External data block ==> No external data in the log
848  EXPECT_FALSE(result.utc.is_initialized());
849 
850  EXPECT_FALSE(result.gnss1.is_initialized());
851 
852  EXPECT_FALSE(result.gnss2.is_initialized());
853 
854  EXPECT_FALSE(result.emlog1.is_initialized());
855 
856  EXPECT_FALSE(result.emlog2.is_initialized());
857 
858  EXPECT_FALSE(result.usbl1.is_initialized());
859 
860  EXPECT_FALSE(result.usbl2.is_initialized());
861 
862  EXPECT_FALSE(result.usbl3.is_initialized());
863 
864  EXPECT_FALSE(result.depth.is_initialized());
865 
866  EXPECT_FALSE(result.dvlGroundSpeed1.is_initialized());
867 
868  EXPECT_FALSE(result.dvlWaterSpeed1.is_initialized());
869 
870  EXPECT_FALSE(result.soundVelocity.is_initialized());
871 
872  EXPECT_FALSE(result.dmi.is_initialized());
873 
874  EXPECT_FALSE(result.lbl1.is_initialized());
875 
876  EXPECT_FALSE(result.lbl2.is_initialized());
877 
878  EXPECT_FALSE(result.lbl3.is_initialized());
879 
880  EXPECT_FALSE(result.lbl4.is_initialized());
881 
882  EXPECT_FALSE(result.eventMarkerA.is_initialized());
883 
884  EXPECT_FALSE(result.eventMarkerB.is_initialized());
885 
886  EXPECT_FALSE(result.eventMarkerC.is_initialized());
887 
888  EXPECT_FALSE(result.dvlGroundSpeed2.is_initialized());
889 
890  EXPECT_FALSE(result.dvlWaterSpeed2.is_initialized());
891 
892  EXPECT_FALSE(result.turretAngles.is_initialized());
893 
894  EXPECT_FALSE(result.vtg1.is_initialized());
895 
896  EXPECT_FALSE(result.vtg2.is_initialized());
897 
898  EXPECT_FALSE(result.logBook.is_initialized());
899 }
900 
901 TEST(StdBinDecoder, WeCanParseV5Protocol)
902 {
904 
905  parser.addNewData(log_STDBIN_V5);
906  ASSERT_TRUE(parser.parseNextFrame());
907  auto result = parser.getLastNavData();
908 
909  // --- Navigation data block
910  EXPECT_TRUE(result.attitudeHeading.is_initialized());
911  EXPECT_FLOAT_EQ(result.attitudeHeading.get().heading_deg, 357.404);
912  EXPECT_FLOAT_EQ(result.attitudeHeading.get().roll_deg, -0.04);
913  EXPECT_FLOAT_EQ(result.attitudeHeading.get().pitch_deg, 0.178);
914 
915  EXPECT_TRUE(result.attitudeHeadingDeviation.is_initialized());
916  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().heading_stdDev_deg, 54.47794);
917  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().roll_stdDev_deg, 0.010677356);
918  EXPECT_FLOAT_EQ(result.attitudeHeadingDeviation.get().pitch_stdDev_deg, 0.016798064);
919 
920  EXPECT_TRUE(result.rtHeaveSurgeSway.is_initialized());
921  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_withoutBdL, 0.0);
922  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_heave_atBdL, 0.0);
923  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_surge_atBdL, 0.0);
924  EXPECT_FLOAT_EQ(result.rtHeaveSurgeSway.get().rt_sway_atBdL, 0.0);
925 
926  EXPECT_TRUE(result.smartHeave.is_initialized());
927  EXPECT_EQ(result.smartHeave.get().validityTime_100us, 8715456); // Sec
928  EXPECT_FLOAT_EQ(result.smartHeave.get().smartHeave_m, 0.0);
929 
930  EXPECT_TRUE(result.headingRollPitchRate.is_initialized());
931  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().heading_rate, -0.002);
932  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().roll_rate, -0.005);
933  EXPECT_FLOAT_EQ(result.headingRollPitchRate.get().pitch_rate, -0.001);
934 
935  EXPECT_TRUE(result.rotationRateVesselFrame.is_initialized());
936  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv1_degsec, -0.006139992);
937  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv2_degsec, -0.0009184938);
938  EXPECT_FLOAT_EQ(result.rotationRateVesselFrame.get().xv3_degsec, 0.0024874974);
939 
940  EXPECT_TRUE(result.accelerationVesselFrame.is_initialized());
941  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv1_msec2, 0.000034999997);
942  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv2_msec2, 0.00041499975);
943  EXPECT_FLOAT_EQ(result.accelerationVesselFrame.get().xv3_msec2, 0.000715);
944 
945  EXPECT_TRUE(result.position.is_initialized());
946  EXPECT_DOUBLE_EQ(result.position.get().latitude_deg, 2.133332701513265);
947  EXPECT_DOUBLE_EQ(result.position.get().longitude_deg, 47.99999983221664);
948  EXPECT_EQ(result.position.get().altitude_ref, 0);
949  EXPECT_FLOAT_EQ(result.position.get().altitude_m, 0.16032125);
950 
951  EXPECT_TRUE(result.positionDeviation.is_initialized());
952  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_stddev_m, 14.204068);
953  EXPECT_FLOAT_EQ(result.positionDeviation.get().east_stddev_m, 14.156303);
954  EXPECT_FLOAT_EQ(result.positionDeviation.get().north_east_corr, 0.03173876);
955  EXPECT_FLOAT_EQ(result.positionDeviation.get().altitude_stddev_m, 2.828566);
956 
957  EXPECT_TRUE(result.speedGeographicFrame.is_initialized());
958  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().north_msec, -0.00031041596);
959  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().east_msec, -0.011805205);
960  EXPECT_FLOAT_EQ(result.speedGeographicFrame.get().up_msec, 0.045028113);
961 
962  EXPECT_TRUE(result.speedGeographicFrameDeviation.is_initialized());
963  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().north_stddev_msec,
964  0.0069630453);
965  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().east_stddev_msec,
966  0.006644114);
967  EXPECT_FLOAT_EQ(result.speedGeographicFrameDeviation.get().up_stddev_msec,
968  0.009995009);
969 
970  EXPECT_TRUE(result.currentGeographicFrame.is_initialized());
971  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().north_msec, 1.919778 * 0.0);
972  EXPECT_FLOAT_EQ(result.currentGeographicFrame.get().east_msec, 4.5171327 * 0.0);
973 
974  EXPECT_TRUE(result.currentGeographicFrameDeviation.is_initialized());
975  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().north_stddev_msec, 0.0);
976  EXPECT_FLOAT_EQ(result.currentGeographicFrameDeviation.get().east_stddev_msec, 0.0);
977 
978  EXPECT_TRUE(result.systemDate.is_initialized());
979  EXPECT_EQ(result.systemDate.get().day, 1);
980  EXPECT_EQ(result.systemDate.get().month, 1);
981  EXPECT_EQ(result.systemDate.get().year, 2006);
982 
983  EXPECT_TRUE(result.sensorStatus.is_initialized());
984  EXPECT_EQ(result.sensorStatus.get().status1, 0x0);
985  EXPECT_EQ(result.sensorStatus.get().status2, 0x0);
986 
987  EXPECT_TRUE(result.insAlgorithmStatus.is_initialized());
988  EXPECT_EQ(result.insAlgorithmStatus.get().status1, 0x00000012);
989  EXPECT_EQ(result.insAlgorithmStatus.get().status2, 0x00030000);
990  EXPECT_EQ(result.insAlgorithmStatus.get().status3, 0x04000000);
991  EXPECT_EQ(result.insAlgorithmStatus.get().status4, 0x00000200);
992 
993  EXPECT_TRUE(result.insSystemStatus.is_initialized());
994  EXPECT_EQ(result.insSystemStatus.get().status1, 0x00000200);
995  EXPECT_EQ(result.insSystemStatus.get().status2, 0x00001000);
996  EXPECT_EQ(result.insSystemStatus.get().status3, 0x0);
997 
998  EXPECT_TRUE(result.insUserStatus.is_initialized());
999  EXPECT_EQ(result.insUserStatus.get().status, 0x4c000000);
1000 
1001  EXPECT_FALSE(result.ahrsAlgorithmStatus.is_initialized());
1002 
1003  EXPECT_FALSE(result.ahrsSystemStatus.is_initialized());
1004 
1005  EXPECT_FALSE(result.ahrsUserStatus.is_initialized());
1006 
1007  EXPECT_TRUE(result.heaveSurgeSwaySpeed.is_initialized());
1008  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().realtime_heave_speed, 0.0);
1009  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().surge_speed, 0.0);
1010  EXPECT_FLOAT_EQ(result.heaveSurgeSwaySpeed.get().sway_speed, 0.0);
1011 
1012  EXPECT_TRUE(result.speedVesselFrame.is_initialized());
1013  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv1_msec, 0.00010496828);
1014  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv2_msec, 0.011636287);
1015  EXPECT_FLOAT_EQ(result.speedVesselFrame.get().xv3_msec, 0.04487192);
1016 
1017  EXPECT_TRUE(result.accelerationGeographicFrame.is_initialized());
1018  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().north_msec2, 0.0);
1019  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().east_msec2, -0.01);
1020  EXPECT_FLOAT_EQ(result.accelerationGeographicFrame.get().up_msec2, 9.809999);
1021 
1022  EXPECT_TRUE(result.courseSpeedoverGround.is_initialized());
1023  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().course_over_ground, 268.6071);
1024  EXPECT_FLOAT_EQ(result.courseSpeedoverGround.get().speed_over_ground, 0.011670535);
1025 
1026  EXPECT_TRUE(result.temperatures.is_initialized());
1027  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_fog, 25.993126);
1028  EXPECT_FLOAT_EQ(result.temperatures.get().mean_temp_acc, 25.993126);
1029  EXPECT_FLOAT_EQ(result.temperatures.get().board_temperature, 158.65643);
1030 
1031  EXPECT_TRUE(result.attitudeQuaternion.is_initialized());
1032  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q0, 0.999742329120636);
1033  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q1, 0.00038825065712444484);
1034  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q2, -0.0015505076153203845);
1035  EXPECT_FLOAT_EQ(result.attitudeQuaternion.get().q3, -0.022644637152552605);
1036 
1037  EXPECT_TRUE(result.attitudeQuaternionDeviation.is_initialized());
1038  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi1,
1039  0.00018635205924510956);
1040  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi2,
1041  0.00029318343149498105);
1042  EXPECT_FLOAT_EQ(result.attitudeQuaternionDeviation.get().quat_stddev_xi3,
1043  0.9508194327354431);
1044 
1045  EXPECT_TRUE(result.rawAccelerationVesselFrame.is_initialized());
1046  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv1_msec2, 0.0);
1047  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv2_msec2, 0.0);
1048  EXPECT_FLOAT_EQ(result.rawAccelerationVesselFrame.get().xv3_msec2, 8.000145);
1049 
1050  EXPECT_TRUE(result.accelerationVesselFrameDeviation.is_initialized());
1051  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv1_stddev_msec2,
1052  0.009960833);
1053  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv2_stddev_msec2,
1054  0.009610326);
1055  EXPECT_FLOAT_EQ(result.accelerationVesselFrameDeviation.get().xv3_stddev_msec2,
1056  0.01413504);
1057 
1058  EXPECT_TRUE(result.rotationRateVesselFrameDeviation.is_initialized());
1059  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv1_stddev_degsec,
1060  0.0005122008);
1061  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv2_stddev_degsec,
1062  0.004000983);
1063  EXPECT_FLOAT_EQ(result.rotationRateVesselFrameDeviation.get().xv3_stddev_degsec,
1064  0.00051041954);
1065 
1066  // --- Extended navigation data block
1067  EXPECT_TRUE(result.rotationAccelerationVesselFrame.is_initialized());
1068  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv1_degsec2,
1069  0.00032014688);
1070  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv2_degsec2,
1071  0.001597333);
1072  EXPECT_FLOAT_EQ(result.rotationAccelerationVesselFrame.get().xv3_degsec2,
1073  -0.00042017436);
1074 
1075  EXPECT_TRUE(result.rotationAccelerationVesselFrameDeviation.is_initialized());
1076  EXPECT_FLOAT_EQ(
1077  result.rotationAccelerationVesselFrameDeviation.get().xv1_stddev_degsec2,
1078  0.000706749);
1079  EXPECT_FLOAT_EQ(
1080  result.rotationAccelerationVesselFrameDeviation.get().xv2_stddev_degsec2,
1081  0.0007067489);
1082  EXPECT_FLOAT_EQ(
1083  result.rotationAccelerationVesselFrameDeviation.get().xv3_stddev_degsec2,
1084  0.000706749);
1085 
1086  EXPECT_TRUE(result.rawRotationRateVesselFrame.is_initialized());
1087  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv1_degsec, 0.0);
1088  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv2_degsec, 0.0);
1089  EXPECT_FLOAT_EQ(result.rawRotationRateVesselFrame.get().xv3_degsec, 0.0);
1090 
1091  EXPECT_FALSE(result.vehicleAttitudeHeading.is_initialized());
1092 
1093  EXPECT_FALSE(result.vehicleAttitudeHeadingDeviation.is_initialized());
1094 
1095  EXPECT_FALSE(result.vehiclePosition.is_initialized());
1096 
1097  EXPECT_FALSE(result.vehiclePositionDeviation.is_initialized());
1098 
1099  // --- External data block ==> No external data in the log
1100  EXPECT_FALSE(result.utc.is_initialized());
1101 
1102  EXPECT_FALSE(result.gnss1.is_initialized());
1103 
1104  EXPECT_FALSE(result.gnss2.is_initialized());
1105 
1106  EXPECT_FALSE(result.emlog1.is_initialized());
1107 
1108  EXPECT_FALSE(result.emlog2.is_initialized());
1109 
1110  EXPECT_FALSE(result.usbl1.is_initialized());
1111 
1112  EXPECT_FALSE(result.usbl2.is_initialized());
1113 
1114  EXPECT_FALSE(result.usbl3.is_initialized());
1115 
1116  EXPECT_FALSE(result.depth.is_initialized());
1117 
1118  EXPECT_FALSE(result.dvlGroundSpeed1.is_initialized());
1119 
1120  EXPECT_FALSE(result.dvlWaterSpeed1.is_initialized());
1121 
1122  EXPECT_FALSE(result.soundVelocity.is_initialized());
1123 
1124  EXPECT_FALSE(result.dmi.is_initialized());
1125 
1126  EXPECT_FALSE(result.lbl1.is_initialized());
1127 
1128  EXPECT_FALSE(result.lbl2.is_initialized());
1129 
1130  EXPECT_FALSE(result.lbl3.is_initialized());
1131 
1132  EXPECT_FALSE(result.lbl4.is_initialized());
1133 
1134  EXPECT_FALSE(result.eventMarkerA.is_initialized());
1135 
1136  EXPECT_FALSE(result.eventMarkerB.is_initialized());
1137 
1138  EXPECT_FALSE(result.eventMarkerC.is_initialized());
1139 
1140  EXPECT_FALSE(result.dvlGroundSpeed2.is_initialized());
1141 
1142  EXPECT_FALSE(result.dvlWaterSpeed2.is_initialized());
1143 
1144  EXPECT_FALSE(result.turretAngles.is_initialized());
1145 
1146  EXPECT_FALSE(result.vtg1.is_initialized());
1147 
1148  EXPECT_FALSE(result.vtg2.is_initialized());
1149 
1150  EXPECT_FALSE(result.logBook.is_initialized());
1151 }
1152 
1153 TEST(StdBinDecoder, WeCanParseAnAnswerFrame)
1154 {
1155  // clang-format off
1156  const std::vector<uint8_t> memory{
1157  'A', 'N', /* IX blue header */
1158  0x03, /* Protocol Version */
1159  0x00, 0x0d, /* Telegram size */
1160  0xde, 0xad, 0xbe, 0xef, /* payload */
1161  0x00, 0x00, 0x03, 0xd7, /* checksum */
1162  };
1163  // clang-format on
1164 
1166  parser.addNewData(memory);
1167  ASSERT_TRUE(parser.parseNextFrame());
1168  const auto header = parser.getLastHeaderData();
1169  const auto nav = parser.getLastNavData();
1170  const auto answer = parser.getLastAnswerData();
1171  ASSERT_EQ(header.messageType,
1173  EXPECT_FALSE(nav.attitudeHeading.is_initialized());
1174  const std::vector<uint8_t> expectedAnswer{0xde, 0xad, 0xbe, 0xef};
1175  EXPECT_EQ(answer, expectedAnswer);
1176 }
1177 
1178 int main(int argc, char** argv)
1179 {
1180  ::testing::InitGoogleTest(&argc, argv);
1181  return RUN_ALL_TESTS();
1182 }
constexpr std::array< uint8_t, 0x25 > BAD_NAV_PROTOCOL_VERSION
void addNewData(const uint8_t *data, std::size_t length)
Add new binary data to the parser internal buffer The new data can only be a part of a frame...
const std::vector< uint8_t > log_STDBIN_V5
Definition: log_STDBIN_V5.h:5
TEST_F(TestStdBinDecoderErrorRecovery, RecoveryFromBadCheckSum)
Data::NavHeader getLastHeaderData(void) const
bool parseNextFrame()
Try to parse a frame from the parser internal buffer. Some binary data must have been added with the ...
constexpr std::array< uint8_t, 0x25 > BAD_CHECK_SUM
Definition: BadCheckSum.h:5
const std::vector< uint8_t > log_STDBIN_V4
Definition: log_STDBIN_V4.h:5
Data::BinaryNav getLastNavData(void) const
constexpr std::array< uint8_t, 0x0d > BAD_ANSWER_PROTOCOL_VERSION
TEST(StdBinDecoder, WeCannotParseAFrameWithSomeMissingFields)
const std::vector< uint8_t > log_STDBIN_V2
Definition: log_STDBIN_V2.h:5
int main(int argc, char **argv)
const std::vector< uint8_t > log_STDBIN_V3
Definition: log_STDBIN_V3.h:5
Parser of a STDBIN IXblue message. This is the entry point of the library. Usage of this class is as ...
const std::vector< uint8_t > & getLastAnswerData(void) const


ixblue_stdbin_decoder
Author(s): Adrien BARRAL , Laure LEBROTON
autogenerated on Wed Apr 6 2022 02:22:12