0.4.1
Loading...
Searching...
No Matches
VectorNavSensor.hpp
Go to the documentation of this file.
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/// @file VectorNavSensor.hpp
10/// @brief Vector Nav Sensors
11/// @author T. Topp (topp@ins.uni-stuttgart.de)
12/// @date 2020-03-12
13
14#pragma once
15
16// VectorNav library includes <winsock2.h>, but <boost/asio.hpp> needs to be included before (even though not used in this file)
17// https://stackoverflow.com/questions/9750344/boostasio-winsock-and-winsock-2-compatibility-issue
18#ifdef _WIN32
19 // Set the proper SDK version before including boost/Asio
20 #include <SDKDDKVer.h>
21 // Note boost/ASIO includes Windows.h.
22 #include <boost/asio.hpp>
23#endif //_WIN32
24
27#include "vn/sensors.h"
28
30
33
34#include <vector>
35#include <array>
36#include <cstdint>
37
38namespace NAV
39{
40class VectorNavFile;
41
42/// Vector Nav Sensor Class
43class VectorNavSensor : public Imu, public UartSensor
44{
45 public:
46 /// Information needed to sync Master/Slave sensors
47 struct TimeSync
48 {
49 InsTime ppsTime; ///< Time of the last message with GNSS Time available (or empty otherwise)
50 uint32_t syncOutCnt{}; ///< The number of SyncOut trigger events that have occurred.
51 };
52
53 /// @brief Default constructor
55 /// @brief Destructor
56 ~VectorNavSensor() override;
57 /// @brief Copy constructor
59 /// @brief Move constructor
61 /// @brief Copy assignment operator
63 /// @brief Move assignment operator
65
66 /// @brief String representation of the Class Type
67 [[nodiscard]] static std::string typeStatic();
68
69 /// @brief String representation of the Class Type
70 [[nodiscard]] std::string type() const override;
71
72 /// @brief String representation of the Class Category
73 [[nodiscard]] static std::string category();
74
75 /// @brief ImGui config window which is shown on double click
76 /// @attention Don't forget to set _hasConfig to true in the constructor of the node
77 void guiConfig() override;
78
79 /// @brief Saves the node into a json object
80 [[nodiscard]] json save() const override;
81
82 /// @brief Restores the node from a json object
83 /// @param[in] j Json object with the node state
84 void restore(const json& j) override;
85
86 /// @brief Resets the node. It is guaranteed that the node is initialized when this is called.
87 bool resetNode() override;
88
89 private:
90 constexpr static size_t OUTPUT_PORT_INDEX_ASCII_OUTPUT = 0; ///< @brief Flow (StringObs)
91
92 /// @brief Initialize the node
93 bool initialize() override;
94
95 /// @brief Deinitialize the node
96 void deinitialize() override;
97
98 /// @brief Merges the content of the two observations into one
99 /// @param[in, out] target The observation used to store the merged information
100 /// @param[in] source The observation where information is taken from
101 static void mergeVectorNavBinaryObservations(const std::shared_ptr<VectorNavBinaryOutput>& target, const std::shared_ptr<VectorNavBinaryOutput>& source);
102
103 /// @brief Callback handler for notifications of new asynchronous data packets received
104 /// @param[in, out] userData Pointer to the data we supplied when we called registerAsyncPacketReceivedHandler
105 /// @param[in] p Encapsulation of the data packet. At this state, it has already been validated and identified as an asynchronous data message
106 /// @param[in] index Advanced usage item and can be safely ignored for now
107 static void asciiOrBinaryAsyncMessageReceived(void* userData, vn::protocol::uart::Packet& p, size_t index);
108
109 /// @brief VectorNav Model enumeration
110 enum class VectorNavModel : uint8_t
111 {
112 /// VN-100/SMD (Miniature, lightweight and high-performance IMU & AHRS)
113 /// VN-110/E (Rugged and Miniature Tactical-Grade IMU and AHRS)
115 /// VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass)
117 };
118
119 /// @brief The sensor model which is selected in the GUI
121
122 /// VnSensor Object
123 vn::sensors::VnSensor _vs;
124
125 /// Connected sensor port
127
128 /// Internal Frequency of the Sensor
129 static constexpr double IMU_DEFAULT_FREQUENCY = 800;
130
131 /// First: List of RateDividers, Second: List of Matching Frequencies
132 std::pair<std::vector<uint16_t>, std::vector<std::string>> _dividerFrequency;
133
134 /// @brief Stores the time of the last received message
135 std::array<InsTime, 3> _lastMessageTime{};
136
137 /// @brief Stores the time of the last received message
138 std::array<uint64_t, 3> _lastMessageTimeSinceStartup{};
139
140 /// @brief Last received GNSS time
141 struct
142 {
143 InsTime lastGnssTime; ///< Last GNSS time received
144 uint64_t timeSinceStartup{}; ///< Time since startup when the GNSS time was received
146
147 // ###########################################################################################################
148 // SYSTEM MODULE
149 // ###########################################################################################################
150
151 /// @brief Async Data Output Type Register
152 /// @note See User manual VN-310 - 8.2.7 (p 92f) / VN-100 - 5.2.7 (p 65)
153 vn::protocol::uart::AsciiAsync _asyncDataOutputType = vn::protocol::uart::AsciiAsync::VNOFF;
154
155 /// @brief Possible values for the Async Data Output Frequency Register
156 /// @note See User manual VN-310 - 8.2.8 (p 94) / VN-100 - 5.2.8 (p 66)
157 static constexpr std::array _possibleAsyncDataOutputFrequency = { 1, 2, 4, 5, 10, 20, 25, 40, 50, 100, 200 };
158
159 /// @brief Async Data Output Frequency Register
160 /// @note See User manual VN-310 - 8.2.8 (p 94) / VN-100 - 5.2.8 (p 66)
162 /// @brief Selected Frequency of the Async Ascii Output in the GUI
164
165 /// @brief Max size of the Ascii Output
167
168 /// @brief Buffer to store Ascii Output Messages
170
171 /// @brief Synchronization Control.
172 ///
173 /// Contains parameters which allow the timing of the VN-310E to be synchronized with external devices.
174 /// @note See User manual VN-310 - 8.2.9 (p 95f) / VN-100 - 5.2.9 (p 67f)
175 vn::sensors::SynchronizationControlRegister _synchronizationControlRegister{
176 vn::protocol::uart::SyncInMode::SYNCINMODE_COUNT, // SyncInMode
177 vn::protocol::uart::SyncInEdge::SYNCINEDGE_RISING, // SyncInEdge
178 0, // SyncInSkipFactor
179 vn::protocol::uart::SyncOutMode::SYNCOUTMODE_NONE, // SyncOutMode
180 vn::protocol::uart::SyncOutPolarity::SYNCOUTPOLARITY_POSITIVE, // SyncOutPolarity
181 0, // SyncOutSkipFactor
182 100000000 // SyncOutPulseWidth
183 };
184
185 /// @brief Time synchronization for master sensors
187
188 /// Show the SyncIn Pin
189 bool _syncInPin = false;
190
191 /// Last received syncInCnt
192 int64_t _lastSyncInCnt = 0;
193
194 /// Last received syncOutCnt
195 int64_t _lastSyncOutCnt = 0;
196
197 /// Offset between syncIn and syncOut
198 int64_t _syncCntOffset = 0;
199
200 /// Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor)
202
203 /// @brief Updates the ImuFilter's rate when pressing the checkbox button
204 /// @param sensor VectorNav sensor (VN100, VN310E, etc.)
205 /// @param bor Binary Output Register
206 /// @param binaryField Binary Field
207 static void coupleImuFilterRates(NAV::VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField);
208
209 /// @brief Communication Protocol Control.
210 ///
211 /// Contains parameters that controls the communication protocol used by the sensor.
212 /// @note See User manual VN-310 - 8.2.10 (p 97ff) / VN-100 - 5.2.10 (p 69ff)
213 vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister{
214 vn::protocol::uart::CountMode::COUNTMODE_NONE, // SerialCount
215 vn::protocol::uart::StatusMode::STATUSMODE_OFF, // SerialStatus
216 vn::protocol::uart::CountMode::COUNTMODE_NONE, // SPICount
217 vn::protocol::uart::StatusMode::STATUSMODE_OFF, // SPIStatus
218 vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CHECKSUM, // SerialChecksum
219 vn::protocol::uart::ChecksumMode::CHECKSUMMODE_OFF, // SPIChecksum
220 vn::protocol::uart::ErrorMode::ERRORMODE_SEND // ErrorMode
221 };
222
223 /// Possible Merge combinations between the binary output registers
224 enum class BinaryRegisterMerge : uint8_t
225 {
226 None, ///< Do not merge any outputs
227 Output1_Output2, ///< Merge Output 1 and 2
228 Output1_Output3, ///< Merge Output 1 and 3
229 Output2_Output3, ///< Merge Output 2 and 3
230 };
231
232 /// Merge binary output registers together. This has to be done because VectorNav sensors have a buffer overflow when packages get too big.
234
235 /// First observation received, which should be merged together
236 std::shared_ptr<VectorNavBinaryOutput> _binaryOutputRegisterMergeObservation = nullptr;
237 /// Index of the binary output for the merge observation stored
239
240 /// @brief Binary Output Register 1 - 3.
241 ///
242 /// This register allows the user to construct a custom binary output message that
243 /// contains a collection of desired estimated states and sensor measurements.
244 /// @note See User manual VN-310 - 8.2.11-13 (p 100ff) / VN-100 - 5.2.11-13 (p 73ff)
245 std::array<vn::sensors::BinaryOutputRegister, 3> _binaryOutputRegister = { vn::sensors::BinaryOutputRegister{
246 vn::protocol::uart::AsyncMode::ASYNCMODE_PORT1, // AsyncMode
247 800, // RateDivisor
248 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup
249 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup
250 vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup
251 vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group
252 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup
253 vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup
254 vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group
255 },
256 vn::sensors::BinaryOutputRegister{
257 vn::protocol::uart::AsyncMode::ASYNCMODE_NONE, // AsyncMode
258 800, // RateDivisor
259 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup
260 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup
261 vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup
262 vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group
263 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup
264 vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup
265 vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group
266 },
267 vn::sensors::BinaryOutputRegister{
268 vn::protocol::uart::AsyncMode::ASYNCMODE_NONE, // AsyncMode
269 800, // RateDivisor
270 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup
271 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup
272 vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup
273 vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group
274 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup
275 vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup
276 vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group
277 } };
278 /// @brief Selected Frequency of the Binary Outputs in the GUI
279 std::array<size_t, 3> _binaryOutputSelectedFrequency{};
280
281 // ###########################################################################################################
282 // IMU SUBSYSTEM
283 // ###########################################################################################################
284
285 /// @brief Reference Frame Rotation.
286 ///
287 /// Allows the measurements of the VN-310E to be rotated into a different reference frame.
288 /// @note See User manual VN-310 - 9.2.4 (p 114) / VN-100 - 6.2.4 (p 85)
289 vn::math::mat3f _referenceFrameRotationMatrix{ { 1, 0, 0 },
290 { 0, 1, 0 },
291 { 0, 0, 1 } };
292
293 /// @brief IMU Filtering Configuration.
294 ///
295 /// Controls the level of filtering performed on the raw IMU measurements.
296 /// @note See User manual VN-310 - 9.2.5 (p 115) / VN-100 - 6.2.5 (p 86)
297 vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister{
298 4, // MagWindowSize
299 4, // AccelWindowSize
300 4, // GyroWindowSize
301 4, // TempWindowSize
302 4, // PresWindowSize
303 vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING, // MagFilterMode
304 vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // AccelFilterMode
305 vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // GyroFilterMode
306 vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // TempFilterMode
307 vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING // PresFilterMode
308 };
309
310 /// @brief Delta Theta and Delta Velocity Configuration.
311 ///
312 /// This register contains configuration options for the internal coning/sculling calculations.
313 /// @note See User manual VN-310 - 9.2.6 (p 116) / VN-100 - 6.2.6 (p 87)
314 vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister{
315 vn::protocol::uart::IntegrationFrame::INTEGRATIONFRAME_BODY, // IntegrationFrame
316 vn::protocol::uart::CompensationMode::COMPENSATIONMODE_NONE, // GyroCompensation
317 vn::protocol::uart::AccCompensationMode::ACCCOMPENSATIONMODE_NONE, // AccelCompensation
318 vn::protocol::uart::EarthRateCorrection::EARTHRATECORR_NONE // EarthRateCorrection
319 };
320
321 // ###########################################################################################################
322 // GNSS SUBSYSTEM
323 // ###########################################################################################################
324
325 /// @brief GNSS Configuration.
326 /// @note See User manual VN-310 - 10.2.1 (p 124)
327 vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister{
328 vn::protocol::uart::GpsMode::GPSMODE_ONBOARDGPS, // Mode
329 vn::protocol::uart::PpsSource::PPSSOURCE_GPSPPSRISING, // PpsSource
330 vn::protocol::uart::GpsRate::GPSRATE_5HZ, // Rate
331 vn::protocol::uart::AntPower::ANTPOWER_INTERNAL // AntPower
332 };
333
334 /// @brief GNSS Antenna A Offset.
335 ///
336 /// Configures the position offset of GNSS antenna A from the VN-310E in the vehicle reference frame.
337 /// @note See User manual VN-310 - 10.2.2 (p 125)
338 vn::math::vec3f _gpsAntennaOffset{
339 0, 0, 0 // [m]
340 };
341
342 /// @brief GNSS Compass Baseline.
343 ///
344 /// Configures the position offset and measurement uncertainty of the second GNSS
345 /// antenna relative to the first GNSS antenna in the vehicle reference frame.
346 /// @note See User manual VN-310 - 10.2.3 (p 126f)
347 vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister{
348 vn::math::vec3f{ 1.0F, 0.0F, 0.0F }, // Position [m]
349 vn::math::vec3f{ 0.254F, 0.254F, 0.254F } // Uncertainty [m]
350 };
351
352 // ###########################################################################################################
353 // ATTITUDE SUBSYSTEM
354 // ###########################################################################################################
355
356 /// @brief VPE Basic Control.
357 ///
358 /// Provides control over various features relating to the onboard attitude filtering algorithm.
359 /// @note See User manual VN-310 - 11.3.1 (p 158) / VN-100 - 7.3.1 (p 104)
360 vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister{
361 vn::protocol::uart::VpeEnable::VPEENABLE_ENABLE, // Enable
362 vn::protocol::uart::HeadingMode::HEADINGMODE_RELATIVE, // HeadingMode
363 vn::protocol::uart::VpeMode::VPEMODE_MODE1, // FilteringMode
364 vn::protocol::uart::VpeMode::VPEMODE_MODE1 // TuningMode
365 };
366
367 /// @brief VPE Magnetometer Basic Tuning.
368 ///
369 /// Provides basic control of the adaptive filtering and tuning for the magnetometer..
370 /// @note See User manual VN-100 - 7.3.2 (p 105)
371 vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister{
372 vn::math::vec3f{ 4.0F, 4.0F, 4.0F }, // BaseTuning [0 - 10]
373 vn::math::vec3f{ 5.0F, 5.0F, 5.0F }, // AdaptiveTuning [0 - 10]
374 vn::math::vec3f{ 5.5F, 5.5F, 5.5F } // AdaptiveFiltering [0 - 10]
375 };
376
377 /// @brief VPE Accelerometer Basic Tuning.
378 ///
379 /// Provides basic control of the adaptive filtering and tuning for the accelerometer.
380 /// @note See User manual VN-100 - 7.3.3 (p 106)
381 vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister{
382 vn::math::vec3f{ 6.0F, 6.0F, 6.0F }, // BaseTuning [0 - 10]
383 vn::math::vec3f{ 3.0F, 3.0F, 3.0F }, // AdaptiveTuning [0 - 10]
384 vn::math::vec3f{ 5.0F, 5.0F, 5.0F } // AdaptiveFiltering [0 - 10]
385 };
386
387 /// @brief VPE Gyro Basic Tuning.
388 ///
389 /// Provides basic control of the adaptive filtering and tuning for the gyro.
390 /// @note See User manual VN-100 - 7.3.5 (p 108)
391 vn::sensors::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister{
392 vn::math::vec3f{ 8.0F, 8.0F, 8.0F }, // VarianceAngularWalk [0 - 10]
393 vn::math::vec3f{ 4.0F, 4.0F, 4.0F }, // BaseTuning [0 - 10]
394 vn::math::vec3f{ 0.0F, 0.0F, 0.0F } // AdaptiveTuning [0 - 10]
395 };
396
397 /// @brief Filter Startup Gyro Bias.
398 ///
399 /// The filter gyro bias estimate used at startup.
400 /// @note See User manual VN-100 - 7.3.4 (p 107)
401 vn::math::vec3f _filterStartupGyroBias{
402 0, 0, 0 // [rad/s]
403 };
404
405 // ###########################################################################################################
406 // INS SUBSYSTEM
407 // ###########################################################################################################
408
409 /// @brief INS Basic Configuration.
410 /// @note See User manual VN-310 - 12.3.1 (p 166)
411 vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300{
412 vn::protocol::uart::Scenario::SCENARIO_GPSMOVINGBASELINEDYNAMIC, // Scenario
413 true, // AhrsAiding
414 true // EstBaseline
415 };
416
417 /// @brief Startup Filter Bias Estimate.
418 ///
419 /// Sets the initial estimate for the filter bias states.
420 /// @note See User manual VN-310 - 12.3.2 (p 167)
421 vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister{
422 vn::math::vec3f{ 0, 0, 0 }, // GyroBias [rad/s]
423 vn::math::vec3f{ 0, 0, 0 }, // AccelBias [m/s^2]
424 0.0F // PressureBiasIn [m]
425 };
426
427 // ###########################################################################################################
428 // HARD/SOFT IRON ESTIMATOR SUBSYSTEM
429 // ###########################################################################################################
430
431 /// @brief Magnetometer Calibration Control.
432 ///
433 /// Controls the magnetometer real-time calibration algorithm.
434 /// @note See User manual VN-310 - 13.1.1 (p 169) / VN-100 - 8.1.1 (p 110)
435 vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister{
436 vn::protocol::uart::HsiMode::HSIMODE_RUN, // HSIMode
437 vn::protocol::uart::HsiOutput::HSIOUTPUT_USEONBOARD, // HSIOutput
438 5 // ConvergeRate
439 };
440
441 // ###########################################################################################################
442 // WORLD MAGNETIC & GRAVITY MODULE
443 // ###########################################################################################################
444
445 /// @brief Magnetic and Gravity Reference Vectors.
446 ///
447 /// Magnetic and gravity reference vectors.
448 /// @note See User manual VN-310 - 14.1.1 (p 175) / VN-100 - 9.1.1 (p 115)
449 vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister{
450 vn::math::vec3f{ 1.0F, 0.0F, 1.8F }, // MagRef [Gauss]
451 vn::math::vec3f{ 0.0F, 0.0F, -9.793746F } // AccRef [m/s^2]
452 };
453
454 /// @brief Reference Vector Configuration.
455 ///
456 /// Control register for both the onboard world magnetic and gravity model corrections.
457 /// @note See User manual VN-310 - 14.1.2 (p 176) / VN-100 - 9.1.2 (p 116)
458 vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister{
459 true, // UseMagModel
460 true, // UseGravityModel
461 1000, // RecalcThreshold [m]
462 0.0F, // Year [years]
463 vn::math::vec3d{ 0, 0, 0 } // Position (Lat Lon Alt [deg deg m])
464 };
465
466 // ###########################################################################################################
467 // VELOCITY AIDING
468 // ###########################################################################################################
469
470 /// @brief Velocity Compensation Control.
471 ///
472 /// Provides control over the velocity compensation feature for the attitude filter.
473 /// @note See User manual VN-100 - 10.2.1 (p 123)
474 vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister{
475 vn::protocol::uart::VelocityCompensationMode::VELOCITYCOMPENSATIONMODE_BODYMEASUREMENT, // Mode
476 0.1F, // VelocityTuning
477 0.01F // RateTuning
478 };
479
480 // ###########################################################################################################
481 // Binary Group GUI Definitions
482 // ###########################################################################################################
483
484 /// @brief Needed data to display a binary group in the GUI
486 {
487 /// Name of the output
488 const char* name = nullptr;
489 /// Enum value of the output
490 int flagsValue = 0;
491 /// Function providing a tooltip
492 void (*tooltip)() = nullptr;
493 /// Function which checks if the ouput is enabled (e.g. for a sensorModel)
494 bool (*isEnabled)(VectorNavModel sensorModel, const vn::sensors::BinaryOutputRegister& bor, uint32_t binaryField) =
495 [](VectorNavModel /* sensorModel */, const vn::sensors::BinaryOutputRegister& /* bor */, uint32_t /* binaryField */) { return true; };
496 /// Function to toggle other bits depending on the status
497 void (*toggleFields)(VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& /* binaryField */) = nullptr;
498 };
499
500 /// @brief Binary group 1 contains a wide assortment of commonly used data required for most applications.
501 ///
502 /// All of the outputs found in group 1 are also present in the other groups. In this sense, group 1 is a subset of
503 /// commonly used outputs from the other groups. This simplifies the configuration of binary output messages for
504 /// applications that only require access to the commonly used data found in group 1. For these applications
505 /// you can hard code the group field to 1, and not worry about implemented support for the other binary groups.
506 /// Using group 1 for commonly used outputs also has the advantage of reducing the overall packet size, since
507 /// the packet length is dependent upon the number of binary groups active.
508 // static const std::array<BinaryGroupData, 15> _binaryGroupCommon;
509
510 /// @brief Binary group 2 provides all timing and event counter related outputs.
511 ///
512 /// Some of these outputs (such as the TimeGps, TimePps, and TimeUtc), require either that the internal GNSS to be
513 /// enabled, or an external GNSS must be present.
514 static const std::array<BinaryGroupData, 10> _binaryGroupTime;
515
516 /// @brief Binary group 3 provides all outputs which are dependent upon the measurements collected from the
517 /// onboard IMU, or an external IMU (if enabled).
518 static const std::array<BinaryGroupData, 11> _binaryGroupIMU;
519
520 /// @brief Binary group 4 provides all outputs which are dependent upon the measurements collected from the primary
521 /// onboard, Binary group 7 from the secondary onboard GNSS, or external GNSS (if enabled).
522 ///
523 /// All data in this group is updated at the rate of the GNSS receiver (nominally 5Hz for the internal GNSS).
524 ///
525 /// @note If data is asynchronously sent from group 4/7 at a rate equal to the GNSS update rate, then packets
526 /// will be sent out when updated by the GNSS receiver. For all other rates, the output will be based
527 /// on the divisor selected and the internal IMU sampling rate.
528 static const std::array<BinaryGroupData, 16> _binaryGroupGNSS;
529
530 /// @brief Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solution.
531 ///
532 /// The attitude will be derived from either the AHRS or the INS, depending upon which filter is currently active and
533 /// tracking. All of the fields in this group will only be valid if the AHRS/INS filter is currently enabled and tracking.
534 static const std::array<BinaryGroupData, 9> _binaryGroupAttitude;
535
536 /// @brief Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution.
537 ///
538 /// All of the fields in this group will only be valid if the INS filter is currently enabled and tracking.
539 static const std::array<BinaryGroupData, 11> _binaryGroupINS;
540
541 friend class NAV::VectorNavFile;
542};
543
544} // namespace NAV
nlohmann::json json
json namespace
Abstract IMU Class.
The class is responsible for all time-related tasks.
A buffer which is overwriting itself from the start when full.
Abstract Uart Sensor Class.
Binary Outputs from VectorNav Sensors.
Imu(const Imu &)=delete
Copy constructor.
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
A buffer which is overwriting itself from the start when full.
UartSensor(const UartSensor &)=delete
Copy constructor.
File Reader for Vector Nav log files.
Vector Nav Sensor Class.
static constexpr size_t OUTPUT_PORT_INDEX_ASCII_OUTPUT
Flow (StringObs)
std::array< vn::sensors::BinaryOutputRegister, 3 > _binaryOutputRegister
Binary Output Register 1 - 3.
int64_t _lastSyncOutCnt
Last received syncOutCnt.
vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister
Magnetometer Calibration Control.
VectorNavSensor(VectorNavSensor &&)=delete
Move constructor.
static std::string typeStatic()
String representation of the Class Type.
std::array< uint64_t, 3 > _lastMessageTimeSinceStartup
Stores the time of the last received message.
static std::string category()
String representation of the Class Category.
vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister
VPE Accelerometer Basic Tuning.
json save() const override
Saves the node into a json object.
vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister
Magnetic and Gravity Reference Vectors.
static constexpr std::array _possibleAsyncDataOutputFrequency
Possible values for the Async Data Output Frequency Register.
int _asyncDataOutputFrequencySelected
Selected Frequency of the Async Ascii Output in the GUI.
std::array< InsTime, 3 > _lastMessageTime
Stores the time of the last received message.
static const std::array< BinaryGroupData, 10 > _binaryGroupTime
Binary group 1 contains a wide assortment of commonly used data required for most applications.
vn::math::vec3f _filterStartupGyroBias
Filter Startup Gyro Bias.
std::string type() const override
String representation of the Class Type.
VectorNavSensor & operator=(VectorNavSensor &&)=delete
Move assignment operator.
static const std::array< BinaryGroupData, 11 > _binaryGroupIMU
Binary group 3 provides all outputs which are dependent upon the measurements collected from the onbo...
VectorNavModel _sensorModel
The sensor model which is selected in the GUI.
bool _coupleImuRateOutput
Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor)
static void coupleImuFilterRates(NAV::VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &binaryField)
Updates the ImuFilter's rate when pressing the checkbox button.
BinaryRegisterMerge
Possible Merge combinations between the binary output registers.
vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister
Delta Theta and Delta Velocity Configuration.
std::shared_ptr< VectorNavBinaryOutput > _binaryOutputRegisterMergeObservation
First observation received, which should be merged together.
void guiConfig() override
ImGui config window which is shown on double click.
vn::sensors::VnSensor _vs
VnSensor Object.
std::string _connectedSensorPort
Connected sensor port.
~VectorNavSensor() override
Destructor.
ScrollingBuffer< std::string > _asciiOutputBuffer
Buffer to store Ascii Output Messages.
vn::sensors::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister
VPE Gyro Basic Tuning.
std::array< size_t, 3 > _binaryOutputSelectedFrequency
Selected Frequency of the Binary Outputs in the GUI.
vn::math::mat3f _referenceFrameRotationMatrix
Reference Frame Rotation.
vn::protocol::uart::AsciiAsync _asyncDataOutputType
Async Data Output Type Register.
vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister
IMU Filtering Configuration.
vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister
GNSS Compass Baseline.
vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister
Startup Filter Bias Estimate.
uint64_t timeSinceStartup
Time since startup when the GNSS time was received.
vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister
GNSS Configuration.
struct NAV::VectorNavSensor::@061131263266062172247357061343017357216211246313 _gnssTimeCounter
Last received GNSS time.
VectorNavSensor()
Default constructor.
void restore(const json &j) override
Restores the node from a json object.
size_t _binaryOutputRegisterMergeIndex
Index of the binary output for the merge observation stored.
static const std::array< BinaryGroupData, 11 > _binaryGroupINS
Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution...
static const std::array< BinaryGroupData, 9 > _binaryGroupAttitude
Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solutio...
VectorNavModel
VectorNav Model enumeration.
@ VN310
VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass)
InsTime lastGnssTime
Last GNSS time received.
vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister
VPE Magnetometer Basic Tuning.
bool initialize() override
Initialize the node.
int _asciiOutputBufferSize
Max size of the Ascii Output.
VectorNavSensor(const VectorNavSensor &)=delete
Copy constructor.
vn::math::vec3f _gpsAntennaOffset
GNSS Antenna A Offset.
static constexpr double IMU_DEFAULT_FREQUENCY
Internal Frequency of the Sensor.
int64_t _syncCntOffset
Offset between syncIn and syncOut.
vn::sensors::SynchronizationControlRegister _synchronizationControlRegister
Synchronization Control.
vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister
VPE Basic Control.
void deinitialize() override
Deinitialize the node.
static void asciiOrBinaryAsyncMessageReceived(void *userData, vn::protocol::uart::Packet &p, size_t index)
Callback handler for notifications of new asynchronous data packets received.
vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister
Communication Protocol Control.
TimeSync _timeSyncOut
Time synchronization for master sensors.
uint32_t _asyncDataOutputFrequency
Async Data Output Frequency Register.
BinaryRegisterMerge _binaryOutputRegisterMerge
Merge binary output registers together. This has to be done because VectorNav sensors have a buffer o...
VectorNavSensor & operator=(const VectorNavSensor &)=delete
Copy assignment operator.
vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister
Reference Vector Configuration.
bool _syncInPin
Show the SyncIn Pin.
vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300
INS Basic Configuration.
std::pair< std::vector< uint16_t >, std::vector< std::string > > _dividerFrequency
First: List of RateDividers, Second: List of Matching Frequencies.
int64_t _lastSyncInCnt
Last received syncInCnt.
bool resetNode() override
Resets the node. It is guaranteed that the node is initialized when this is called.
static const std::array< BinaryGroupData, 16 > _binaryGroupGNSS
Binary group 4 provides all outputs which are dependent upon the measurements collected from the prim...
vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister
Velocity Compensation Control.
static void mergeVectorNavBinaryObservations(const std::shared_ptr< VectorNavBinaryOutput > &target, const std::shared_ptr< VectorNavBinaryOutput > &source)
Merges the content of the two observations into one.
Needed data to display a binary group in the GUI.
void(* toggleFields)(VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &)
Function to toggle other bits depending on the status.
int flagsValue
Enum value of the output.
void(* tooltip)()
Function providing a tooltip.
const char * name
Name of the output.
bool(* isEnabled)(VectorNavModel sensorModel, const vn::sensors::BinaryOutputRegister &bor, uint32_t binaryField)
Function which checks if the ouput is enabled (e.g. for a sensorModel)
Information needed to sync Master/Slave sensors.
InsTime ppsTime
Time of the last message with GNSS Time available (or empty otherwise)
uint32_t syncOutCnt
The number of SyncOut trigger events that have occurred.