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 |
|
|
/// @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 |
|
|
|
25 |
|
|
#include "Nodes/DataProvider/IMU/Imu.hpp" |
26 |
|
|
#include "Nodes/DataProvider/Protocol/UartSensor.hpp" |
27 |
|
|
#include "vn/sensors.h" |
28 |
|
|
|
29 |
|
|
#include "NodeData/IMU/VectorNavBinaryOutput.hpp" |
30 |
|
|
|
31 |
|
|
#include "Navigation/Time/InsTime.hpp" |
32 |
|
|
#include "util/Container/ScrollingBuffer.hpp" |
33 |
|
|
|
34 |
|
|
#include <vector> |
35 |
|
|
#include <array> |
36 |
|
|
#include <cstdint> |
37 |
|
|
|
38 |
|
|
namespace NAV |
39 |
|
|
{ |
40 |
|
|
class VectorNavFile; |
41 |
|
|
|
42 |
|
|
/// Vector Nav Sensor Class |
43 |
|
|
class 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 |
54 |
|
|
VectorNavSensor(); |
55 |
|
|
/// @brief Destructor |
56 |
|
|
~VectorNavSensor() override; |
57 |
|
|
/// @brief Copy constructor |
58 |
|
|
VectorNavSensor(const VectorNavSensor&) = delete; |
59 |
|
|
/// @brief Move constructor |
60 |
|
|
VectorNavSensor(VectorNavSensor&&) = delete; |
61 |
|
|
/// @brief Copy assignment operator |
62 |
|
|
VectorNavSensor& operator=(const VectorNavSensor&) = delete; |
63 |
|
|
/// @brief Move assignment operator |
64 |
|
|
VectorNavSensor& operator=(VectorNavSensor&&) = delete; |
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) |
114 |
|
|
VN100_VN110, |
115 |
|
|
/// VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass) |
116 |
|
|
VN310, |
117 |
|
|
}; |
118 |
|
|
|
119 |
|
|
/// @brief The sensor model which is selected in the GUI |
120 |
|
|
VectorNavModel _sensorModel = VectorNavModel::VN100_VN110; |
121 |
|
|
|
122 |
|
|
/// VnSensor Object |
123 |
|
|
vn::sensors::VnSensor _vs; |
124 |
|
|
|
125 |
|
|
/// Connected sensor port |
126 |
|
|
std::string _connectedSensorPort; |
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 |
145 |
|
|
} _gnssTimeCounter; |
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) |
161 |
|
|
uint32_t _asyncDataOutputFrequency = 40; |
162 |
|
|
/// @brief Selected Frequency of the Async Ascii Output in the GUI |
163 |
|
|
int _asyncDataOutputFrequencySelected = 7; |
164 |
|
|
|
165 |
|
|
/// @brief Max size of the Ascii Output |
166 |
|
|
int _asciiOutputBufferSize = 10; |
167 |
|
|
|
168 |
|
|
/// @brief Buffer to store Ascii Output Messages |
169 |
|
|
ScrollingBuffer<std::string> _asciiOutputBuffer{ static_cast<size_t>(_asciiOutputBufferSize) }; |
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 |
186 |
|
|
TimeSync _timeSyncOut; |
187 |
|
|
|
188 |
|
|
/// Show the SyncIn Pin |
189 |
|
|
bool _syncInPin = false; |
190 |
|
|
|
191 |
|
|
/// Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor) |
192 |
|
|
bool _coupleImuRateOutput = true; |
193 |
|
|
|
194 |
|
|
/// @brief Updates the ImuFilter's rate when pressing the checkbox button |
195 |
|
|
/// @param sensor VectorNav sensor (VN100, VN310E, etc.) |
196 |
|
|
/// @param bor Binary Output Register |
197 |
|
|
/// @param binaryField Binary Field |
198 |
|
|
static void coupleImuFilterRates(NAV::VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField); |
199 |
|
|
|
200 |
|
|
/// @brief Communication Protocol Control. |
201 |
|
|
/// |
202 |
|
|
/// Contains parameters that controls the communication protocol used by the sensor. |
203 |
|
|
/// @note See User manual VN-310 - 8.2.10 (p 97ff) / VN-100 - 5.2.10 (p 69ff) |
204 |
|
|
vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister{ |
205 |
|
|
vn::protocol::uart::CountMode::COUNTMODE_NONE, // SerialCount |
206 |
|
|
vn::protocol::uart::StatusMode::STATUSMODE_OFF, // SerialStatus |
207 |
|
|
vn::protocol::uart::CountMode::COUNTMODE_NONE, // SPICount |
208 |
|
|
vn::protocol::uart::StatusMode::STATUSMODE_OFF, // SPIStatus |
209 |
|
|
vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CHECKSUM, // SerialChecksum |
210 |
|
|
vn::protocol::uart::ChecksumMode::CHECKSUMMODE_OFF, // SPIChecksum |
211 |
|
|
vn::protocol::uart::ErrorMode::ERRORMODE_SEND // ErrorMode |
212 |
|
|
}; |
213 |
|
|
|
214 |
|
|
/// Possible Merge combinations between the binary output registers |
215 |
|
|
enum class BinaryRegisterMerge : uint8_t |
216 |
|
|
{ |
217 |
|
|
None, ///< Do not merge any outputs |
218 |
|
|
Output1_Output2, ///< Merge Output 1 and 2 |
219 |
|
|
Output1_Output3, ///< Merge Output 1 and 3 |
220 |
|
|
Output2_Output3, ///< Merge Output 2 and 3 |
221 |
|
|
}; |
222 |
|
|
|
223 |
|
|
/// Merge binary output registers together. This has to be done because VectorNav sensors have a buffer overflow when packages get too big. |
224 |
|
|
BinaryRegisterMerge _binaryOutputRegisterMerge = BinaryRegisterMerge::None; |
225 |
|
|
|
226 |
|
|
/// First observation received, which should be merged together |
227 |
|
|
std::shared_ptr<VectorNavBinaryOutput> _binaryOutputRegisterMergeObservation = nullptr; |
228 |
|
|
/// Index of the binary output for the merge observation stored |
229 |
|
|
size_t _binaryOutputRegisterMergeIndex{}; |
230 |
|
|
|
231 |
|
|
/// @brief Binary Output Register 1 - 3. |
232 |
|
|
/// |
233 |
|
|
/// This register allows the user to construct a custom binary output message that |
234 |
|
|
/// contains a collection of desired estimated states and sensor measurements. |
235 |
|
|
/// @note See User manual VN-310 - 8.2.11-13 (p 100ff) / VN-100 - 5.2.11-13 (p 73ff) |
236 |
|
|
std::array<vn::sensors::BinaryOutputRegister, 3> _binaryOutputRegister = { vn::sensors::BinaryOutputRegister{ |
237 |
|
|
vn::protocol::uart::AsyncMode::ASYNCMODE_PORT1, // AsyncMode |
238 |
|
|
800, // RateDivisor |
239 |
|
|
vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup |
240 |
|
|
vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup |
241 |
|
|
vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup |
242 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group |
243 |
|
|
vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup |
244 |
|
|
vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup |
245 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group |
246 |
|
|
}, |
247 |
|
|
vn::sensors::BinaryOutputRegister{ |
248 |
|
|
vn::protocol::uart::AsyncMode::ASYNCMODE_NONE, // AsyncMode |
249 |
|
|
800, // RateDivisor |
250 |
|
|
vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup |
251 |
|
|
vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup |
252 |
|
|
vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup |
253 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group |
254 |
|
|
vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup |
255 |
|
|
vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup |
256 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group |
257 |
|
|
}, |
258 |
|
|
vn::sensors::BinaryOutputRegister{ |
259 |
|
|
vn::protocol::uart::AsyncMode::ASYNCMODE_NONE, // AsyncMode |
260 |
|
|
800, // RateDivisor |
261 |
|
|
vn::protocol::uart::CommonGroup::COMMONGROUP_NONE, // CommonGroup |
262 |
|
|
vn::protocol::uart::TimeGroup::TIMEGROUP_NONE, // TimeGroup |
263 |
|
|
vn::protocol::uart::ImuGroup::IMUGROUP_NONE, // IMUGroup |
264 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE, // GNSS1Group |
265 |
|
|
vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE, // AttitudeGroup |
266 |
|
|
vn::protocol::uart::InsGroup::INSGROUP_NONE, // INSGroup |
267 |
|
|
vn::protocol::uart::GpsGroup::GPSGROUP_NONE // GNSS2Group |
268 |
|
|
} }; |
269 |
|
|
/// @brief Selected Frequency of the Binary Outputs in the GUI |
270 |
|
|
std::array<size_t, 3> _binaryOutputSelectedFrequency{}; |
271 |
|
|
|
272 |
|
|
// ########################################################################################################### |
273 |
|
|
// IMU SUBSYSTEM |
274 |
|
|
// ########################################################################################################### |
275 |
|
|
|
276 |
|
|
/// @brief Reference Frame Rotation. |
277 |
|
|
/// |
278 |
|
|
/// Allows the measurements of the VN-310E to be rotated into a different reference frame. |
279 |
|
|
/// @note See User manual VN-310 - 9.2.4 (p 114) / VN-100 - 6.2.4 (p 85) |
280 |
|
|
vn::math::mat3f _referenceFrameRotationMatrix{ { 1, 0, 0 }, |
281 |
|
|
{ 0, 1, 0 }, |
282 |
|
|
{ 0, 0, 1 } }; |
283 |
|
|
|
284 |
|
|
/// @brief IMU Filtering Configuration. |
285 |
|
|
/// |
286 |
|
|
/// Controls the level of filtering performed on the raw IMU measurements. |
287 |
|
|
/// @note See User manual VN-310 - 9.2.5 (p 115) / VN-100 - 6.2.5 (p 86) |
288 |
|
|
vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister{ |
289 |
|
|
4, // MagWindowSize |
290 |
|
|
4, // AccelWindowSize |
291 |
|
|
4, // GyroWindowSize |
292 |
|
|
4, // TempWindowSize |
293 |
|
|
4, // PresWindowSize |
294 |
|
|
vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING, // MagFilterMode |
295 |
|
|
vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // AccelFilterMode |
296 |
|
|
vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // GyroFilterMode |
297 |
|
|
vn::protocol::uart::FilterMode::FILTERMODE_BOTH, // TempFilterMode |
298 |
|
|
vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING // PresFilterMode |
299 |
|
|
}; |
300 |
|
|
|
301 |
|
|
/// @brief Delta Theta and Delta Velocity Configuration. |
302 |
|
|
/// |
303 |
|
|
/// This register contains configuration options for the internal coning/sculling calculations. |
304 |
|
|
/// @note See User manual VN-310 - 9.2.6 (p 116) / VN-100 - 6.2.6 (p 87) |
305 |
|
|
vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister{ |
306 |
|
|
vn::protocol::uart::IntegrationFrame::INTEGRATIONFRAME_BODY, // IntegrationFrame |
307 |
|
|
vn::protocol::uart::CompensationMode::COMPENSATIONMODE_NONE, // GyroCompensation |
308 |
|
|
vn::protocol::uart::AccCompensationMode::ACCCOMPENSATIONMODE_NONE, // AccelCompensation |
309 |
|
|
vn::protocol::uart::EarthRateCorrection::EARTHRATECORR_NONE // EarthRateCorrection |
310 |
|
|
}; |
311 |
|
|
|
312 |
|
|
// ########################################################################################################### |
313 |
|
|
// GNSS SUBSYSTEM |
314 |
|
|
// ########################################################################################################### |
315 |
|
|
|
316 |
|
|
/// @brief GNSS Configuration. |
317 |
|
|
/// @note See User manual VN-310 - 10.2.1 (p 124) |
318 |
|
|
vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister{ |
319 |
|
|
vn::protocol::uart::GpsMode::GPSMODE_ONBOARDGPS, // Mode |
320 |
|
|
vn::protocol::uart::PpsSource::PPSSOURCE_GPSPPSRISING, // PpsSource |
321 |
|
|
vn::protocol::uart::GpsRate::GPSRATE_5HZ, // Rate |
322 |
|
|
vn::protocol::uart::AntPower::ANTPOWER_INTERNAL // AntPower |
323 |
|
|
}; |
324 |
|
|
|
325 |
|
|
/// @brief GNSS Antenna A Offset. |
326 |
|
|
/// |
327 |
|
|
/// Configures the position offset of GNSS antenna A from the VN-310E in the vehicle reference frame. |
328 |
|
|
/// @note See User manual VN-310 - 10.2.2 (p 125) |
329 |
|
|
vn::math::vec3f _gpsAntennaOffset{ |
330 |
|
|
0, 0, 0 // [m] |
331 |
|
|
}; |
332 |
|
|
|
333 |
|
|
/// @brief GNSS Compass Baseline. |
334 |
|
|
/// |
335 |
|
|
/// Configures the position offset and measurement uncertainty of the second GNSS |
336 |
|
|
/// antenna relative to the first GNSS antenna in the vehicle reference frame. |
337 |
|
|
/// @note See User manual VN-310 - 10.2.3 (p 126f) |
338 |
|
|
vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister{ |
339 |
|
112 |
vn::math::vec3f{ 1.0F, 0.0F, 0.0F }, // Position [m] |
340 |
|
112 |
vn::math::vec3f{ 0.254F, 0.254F, 0.254F } // Uncertainty [m] |
341 |
|
|
}; |
342 |
|
|
|
343 |
|
|
// ########################################################################################################### |
344 |
|
|
// ATTITUDE SUBSYSTEM |
345 |
|
|
// ########################################################################################################### |
346 |
|
|
|
347 |
|
|
/// @brief VPE Basic Control. |
348 |
|
|
/// |
349 |
|
|
/// Provides control over various features relating to the onboard attitude filtering algorithm. |
350 |
|
|
/// @note See User manual VN-310 - 11.3.1 (p 158) / VN-100 - 7.3.1 (p 104) |
351 |
|
|
vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister{ |
352 |
|
|
vn::protocol::uart::VpeEnable::VPEENABLE_ENABLE, // Enable |
353 |
|
|
vn::protocol::uart::HeadingMode::HEADINGMODE_RELATIVE, // HeadingMode |
354 |
|
|
vn::protocol::uart::VpeMode::VPEMODE_MODE1, // FilteringMode |
355 |
|
|
vn::protocol::uart::VpeMode::VPEMODE_MODE1 // TuningMode |
356 |
|
|
}; |
357 |
|
|
|
358 |
|
|
/// @brief VPE Magnetometer Basic Tuning. |
359 |
|
|
/// |
360 |
|
|
/// Provides basic control of the adaptive filtering and tuning for the magnetometer.. |
361 |
|
|
/// @note See User manual VN-100 - 7.3.2 (p 105) |
362 |
|
|
vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister{ |
363 |
|
112 |
vn::math::vec3f{ 4.0F, 4.0F, 4.0F }, // BaseTuning [0 - 10] |
364 |
|
112 |
vn::math::vec3f{ 5.0F, 5.0F, 5.0F }, // AdaptiveTuning [0 - 10] |
365 |
|
112 |
vn::math::vec3f{ 5.5F, 5.5F, 5.5F } // AdaptiveFiltering [0 - 10] |
366 |
|
|
}; |
367 |
|
|
|
368 |
|
|
/// @brief VPE Accelerometer Basic Tuning. |
369 |
|
|
/// |
370 |
|
|
/// Provides basic control of the adaptive filtering and tuning for the accelerometer. |
371 |
|
|
/// @note See User manual VN-100 - 7.3.3 (p 106) |
372 |
|
|
vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister{ |
373 |
|
112 |
vn::math::vec3f{ 6.0F, 6.0F, 6.0F }, // BaseTuning [0 - 10] |
374 |
|
112 |
vn::math::vec3f{ 3.0F, 3.0F, 3.0F }, // AdaptiveTuning [0 - 10] |
375 |
|
112 |
vn::math::vec3f{ 5.0F, 5.0F, 5.0F } // AdaptiveFiltering [0 - 10] |
376 |
|
|
}; |
377 |
|
|
|
378 |
|
|
/// @brief VPE Gyro Basic Tuning. |
379 |
|
|
/// |
380 |
|
|
/// Provides basic control of the adaptive filtering and tuning for the gyro. |
381 |
|
|
/// @note See User manual VN-100 - 7.3.5 (p 108) |
382 |
|
|
vn::sensors::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister{ |
383 |
|
112 |
vn::math::vec3f{ 8.0F, 8.0F, 8.0F }, // VarianceAngularWalk [0 - 10] |
384 |
|
112 |
vn::math::vec3f{ 4.0F, 4.0F, 4.0F }, // BaseTuning [0 - 10] |
385 |
|
112 |
vn::math::vec3f{ 0.0F, 0.0F, 0.0F } // AdaptiveTuning [0 - 10] |
386 |
|
|
}; |
387 |
|
|
|
388 |
|
|
/// @brief Filter Startup Gyro Bias. |
389 |
|
|
/// |
390 |
|
|
/// The filter gyro bias estimate used at startup. |
391 |
|
|
/// @note See User manual VN-100 - 7.3.4 (p 107) |
392 |
|
|
vn::math::vec3f _filterStartupGyroBias{ |
393 |
|
|
0, 0, 0 // [rad/s] |
394 |
|
|
}; |
395 |
|
|
|
396 |
|
|
// ########################################################################################################### |
397 |
|
|
// INS SUBSYSTEM |
398 |
|
|
// ########################################################################################################### |
399 |
|
|
|
400 |
|
|
/// @brief INS Basic Configuration. |
401 |
|
|
/// @note See User manual VN-310 - 12.3.1 (p 166) |
402 |
|
|
vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300{ |
403 |
|
|
vn::protocol::uart::Scenario::SCENARIO_GPSMOVINGBASELINEDYNAMIC, // Scenario |
404 |
|
|
true, // AhrsAiding |
405 |
|
|
true // EstBaseline |
406 |
|
|
}; |
407 |
|
|
|
408 |
|
|
/// @brief Startup Filter Bias Estimate. |
409 |
|
|
/// |
410 |
|
|
/// Sets the initial estimate for the filter bias states. |
411 |
|
|
/// @note See User manual VN-310 - 12.3.2 (p 167) |
412 |
|
|
vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister{ |
413 |
|
|
vn::math::vec3f{ 0, 0, 0 }, // GyroBias [rad/s] |
414 |
|
|
vn::math::vec3f{ 0, 0, 0 }, // AccelBias [m/s^2] |
415 |
|
|
0.0F // PressureBiasIn [m] |
416 |
|
|
}; |
417 |
|
|
|
418 |
|
|
// ########################################################################################################### |
419 |
|
|
// HARD/SOFT IRON ESTIMATOR SUBSYSTEM |
420 |
|
|
// ########################################################################################################### |
421 |
|
|
|
422 |
|
|
/// @brief Magnetometer Calibration Control. |
423 |
|
|
/// |
424 |
|
|
/// Controls the magnetometer real-time calibration algorithm. |
425 |
|
|
/// @note See User manual VN-310 - 13.1.1 (p 169) / VN-100 - 8.1.1 (p 110) |
426 |
|
|
vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister{ |
427 |
|
|
vn::protocol::uart::HsiMode::HSIMODE_RUN, // HSIMode |
428 |
|
|
vn::protocol::uart::HsiOutput::HSIOUTPUT_USEONBOARD, // HSIOutput |
429 |
|
|
5 // ConvergeRate |
430 |
|
|
}; |
431 |
|
|
|
432 |
|
|
// ########################################################################################################### |
433 |
|
|
// WORLD MAGNETIC & GRAVITY MODULE |
434 |
|
|
// ########################################################################################################### |
435 |
|
|
|
436 |
|
|
/// @brief Magnetic and Gravity Reference Vectors. |
437 |
|
|
/// |
438 |
|
|
/// Magnetic and gravity reference vectors. |
439 |
|
|
/// @note See User manual VN-310 - 14.1.1 (p 175) / VN-100 - 9.1.1 (p 115) |
440 |
|
|
vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister{ |
441 |
|
112 |
vn::math::vec3f{ 1.0F, 0.0F, 1.8F }, // MagRef [Gauss] |
442 |
|
112 |
vn::math::vec3f{ 0.0F, 0.0F, -9.793746F } // AccRef [m/s^2] |
443 |
|
|
}; |
444 |
|
|
|
445 |
|
|
/// @brief Reference Vector Configuration. |
446 |
|
|
/// |
447 |
|
|
/// Control register for both the onboard world magnetic and gravity model corrections. |
448 |
|
|
/// @note See User manual VN-310 - 14.1.2 (p 176) / VN-100 - 9.1.2 (p 116) |
449 |
|
|
vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister{ |
450 |
|
|
true, // UseMagModel |
451 |
|
|
true, // UseGravityModel |
452 |
|
|
1000, // RecalcThreshold [m] |
453 |
|
|
0.0F, // Year [years] |
454 |
|
|
vn::math::vec3d{ 0, 0, 0 } // Position (Lat Lon Alt [deg deg m]) |
455 |
|
|
}; |
456 |
|
|
|
457 |
|
|
// ########################################################################################################### |
458 |
|
|
// VELOCITY AIDING |
459 |
|
|
// ########################################################################################################### |
460 |
|
|
|
461 |
|
|
/// @brief Velocity Compensation Control. |
462 |
|
|
/// |
463 |
|
|
/// Provides control over the velocity compensation feature for the attitude filter. |
464 |
|
|
/// @note See User manual VN-100 - 10.2.1 (p 123) |
465 |
|
|
vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister{ |
466 |
|
|
vn::protocol::uart::VelocityCompensationMode::VELOCITYCOMPENSATIONMODE_BODYMEASUREMENT, // Mode |
467 |
|
|
0.1F, // VelocityTuning |
468 |
|
|
0.01F // RateTuning |
469 |
|
|
}; |
470 |
|
|
|
471 |
|
|
// ########################################################################################################### |
472 |
|
|
// Binary Group GUI Definitions |
473 |
|
|
// ########################################################################################################### |
474 |
|
|
|
475 |
|
|
/// @brief Needed data to display a binary group in the GUI |
476 |
|
|
struct BinaryGroupData |
477 |
|
|
{ |
478 |
|
|
/// Name of the output |
479 |
|
|
const char* name = nullptr; |
480 |
|
|
/// Enum value of the output |
481 |
|
|
int flagsValue = 0; |
482 |
|
|
/// Function providing a tooltip |
483 |
|
|
void (*tooltip)() = nullptr; |
484 |
|
|
/// Function which checks if the ouput is enabled (e.g. for a sensorModel) |
485 |
|
|
bool (*isEnabled)(VectorNavModel sensorModel, const vn::sensors::BinaryOutputRegister& bor, uint32_t binaryField) = |
486 |
|
✗ |
[](VectorNavModel /* sensorModel */, const vn::sensors::BinaryOutputRegister& /* bor */, uint32_t /* binaryField */) { return true; }; |
487 |
|
|
/// Function to toggle other bits depending on the status |
488 |
|
|
void (*toggleFields)(VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& /* binaryField */) = nullptr; |
489 |
|
|
}; |
490 |
|
|
|
491 |
|
|
/// @brief Binary group 1 contains a wide assortment of commonly used data required for most applications. |
492 |
|
|
/// |
493 |
|
|
/// All of the outputs found in group 1 are also present in the other groups. In this sense, group 1 is a subset of |
494 |
|
|
/// commonly used outputs from the other groups. This simplifies the configuration of binary output messages for |
495 |
|
|
/// applications that only require access to the commonly used data found in group 1. For these applications |
496 |
|
|
/// you can hard code the group field to 1, and not worry about implemented support for the other binary groups. |
497 |
|
|
/// Using group 1 for commonly used outputs also has the advantage of reducing the overall packet size, since |
498 |
|
|
/// the packet length is dependent upon the number of binary groups active. |
499 |
|
|
// static const std::array<BinaryGroupData, 15> _binaryGroupCommon; |
500 |
|
|
|
501 |
|
|
/// @brief Binary group 2 provides all timing and event counter related outputs. |
502 |
|
|
/// |
503 |
|
|
/// Some of these outputs (such as the TimeGps, TimePps, and TimeUtc), require either that the internal GNSS to be |
504 |
|
|
/// enabled, or an external GNSS must be present. |
505 |
|
|
static const std::array<BinaryGroupData, 10> _binaryGroupTime; |
506 |
|
|
|
507 |
|
|
/// @brief Binary group 3 provides all outputs which are dependent upon the measurements collected from the |
508 |
|
|
/// onboard IMU, or an external IMU (if enabled). |
509 |
|
|
static const std::array<BinaryGroupData, 11> _binaryGroupIMU; |
510 |
|
|
|
511 |
|
|
/// @brief Binary group 4 provides all outputs which are dependent upon the measurements collected from the primary |
512 |
|
|
/// onboard, Binary group 7 from the secondary onboard GNSS, or external GNSS (if enabled). |
513 |
|
|
/// |
514 |
|
|
/// All data in this group is updated at the rate of the GNSS receiver (nominally 5Hz for the internal GNSS). |
515 |
|
|
/// |
516 |
|
|
/// @note If data is asynchronously sent from group 4/7 at a rate equal to the GNSS update rate, then packets |
517 |
|
|
/// will be sent out when updated by the GNSS receiver. For all other rates, the output will be based |
518 |
|
|
/// on the divisor selected and the internal IMU sampling rate. |
519 |
|
|
static const std::array<BinaryGroupData, 16> _binaryGroupGNSS; |
520 |
|
|
|
521 |
|
|
/// @brief Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solution. |
522 |
|
|
/// |
523 |
|
|
/// The attitude will be derived from either the AHRS or the INS, depending upon which filter is currently active and |
524 |
|
|
/// tracking. All of the fields in this group will only be valid if the AHRS/INS filter is currently enabled and tracking. |
525 |
|
|
static const std::array<BinaryGroupData, 9> _binaryGroupAttitude; |
526 |
|
|
|
527 |
|
|
/// @brief Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution. |
528 |
|
|
/// |
529 |
|
|
/// All of the fields in this group will only be valid if the INS filter is currently enabled and tracking. |
530 |
|
|
static const std::array<BinaryGroupData, 11> _binaryGroupINS; |
531 |
|
|
|
532 |
|
|
friend class NAV::VectorNavFile; |
533 |
|
|
}; |
534 |
|
|
|
535 |
|
|
} // namespace NAV |
536 |
|
|
|