20 #include <SDKDDKVer.h>
22 #include <boost/asio.hpp>
27#include "vn/sensors.h"
70 [[nodiscard]] std::string
type()
const override;
123 vn::sensors::VnSensor
_vs;
157 static constexpr std::array
_possibleAsyncDataOutputFrequency = { 1, 2, 4, 5, 10, 20, 25, 40, 50, 100, 200 };
176 vn::protocol::uart::SyncInMode::SYNCINMODE_COUNT,
177 vn::protocol::uart::SyncInEdge::SYNCINEDGE_RISING,
179 vn::protocol::uart::SyncOutMode::SYNCOUTMODE_NONE,
180 vn::protocol::uart::SyncOutPolarity::SYNCOUTPOLARITY_POSITIVE,
205 vn::protocol::uart::CountMode::COUNTMODE_NONE,
206 vn::protocol::uart::StatusMode::STATUSMODE_OFF,
207 vn::protocol::uart::CountMode::COUNTMODE_NONE,
208 vn::protocol::uart::StatusMode::STATUSMODE_OFF,
209 vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CHECKSUM,
210 vn::protocol::uart::ChecksumMode::CHECKSUMMODE_OFF,
211 vn::protocol::uart::ErrorMode::ERRORMODE_SEND
237 vn::protocol::uart::AsyncMode::ASYNCMODE_PORT1,
239 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE,
240 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE,
241 vn::protocol::uart::ImuGroup::IMUGROUP_NONE,
242 vn::protocol::uart::GpsGroup::GPSGROUP_NONE,
243 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE,
244 vn::protocol::uart::InsGroup::INSGROUP_NONE,
245 vn::protocol::uart::GpsGroup::GPSGROUP_NONE
247 vn::sensors::BinaryOutputRegister{
248 vn::protocol::uart::AsyncMode::ASYNCMODE_NONE,
250 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE,
251 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE,
252 vn::protocol::uart::ImuGroup::IMUGROUP_NONE,
253 vn::protocol::uart::GpsGroup::GPSGROUP_NONE,
254 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE,
255 vn::protocol::uart::InsGroup::INSGROUP_NONE,
256 vn::protocol::uart::GpsGroup::GPSGROUP_NONE
258 vn::sensors::BinaryOutputRegister{
259 vn::protocol::uart::AsyncMode::ASYNCMODE_NONE,
261 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE,
262 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE,
263 vn::protocol::uart::ImuGroup::IMUGROUP_NONE,
264 vn::protocol::uart::GpsGroup::GPSGROUP_NONE,
265 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE,
266 vn::protocol::uart::InsGroup::INSGROUP_NONE,
267 vn::protocol::uart::GpsGroup::GPSGROUP_NONE
294 vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING,
295 vn::protocol::uart::FilterMode::FILTERMODE_BOTH,
296 vn::protocol::uart::FilterMode::FILTERMODE_BOTH,
297 vn::protocol::uart::FilterMode::FILTERMODE_BOTH,
298 vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING
306 vn::protocol::uart::IntegrationFrame::INTEGRATIONFRAME_BODY,
307 vn::protocol::uart::CompensationMode::COMPENSATIONMODE_NONE,
308 vn::protocol::uart::AccCompensationMode::ACCCOMPENSATIONMODE_NONE,
309 vn::protocol::uart::EarthRateCorrection::EARTHRATECORR_NONE
319 vn::protocol::uart::GpsMode::GPSMODE_ONBOARDGPS,
320 vn::protocol::uart::PpsSource::PPSSOURCE_GPSPPSRISING,
321 vn::protocol::uart::GpsRate::GPSRATE_5HZ,
322 vn::protocol::uart::AntPower::ANTPOWER_INTERNAL
339 vn::math::vec3f{ 1.0F, 0.0F, 0.0F },
340 vn::math::vec3f{ 0.254F, 0.254F, 0.254F }
352 vn::protocol::uart::VpeEnable::VPEENABLE_ENABLE,
353 vn::protocol::uart::HeadingMode::HEADINGMODE_RELATIVE,
354 vn::protocol::uart::VpeMode::VPEMODE_MODE1,
355 vn::protocol::uart::VpeMode::VPEMODE_MODE1
363 vn::math::vec3f{ 4.0F, 4.0F, 4.0F },
364 vn::math::vec3f{ 5.0F, 5.0F, 5.0F },
365 vn::math::vec3f{ 5.5F, 5.5F, 5.5F }
373 vn::math::vec3f{ 6.0F, 6.0F, 6.0F },
374 vn::math::vec3f{ 3.0F, 3.0F, 3.0F },
375 vn::math::vec3f{ 5.0F, 5.0F, 5.0F }
383 vn::math::vec3f{ 8.0F, 8.0F, 8.0F },
384 vn::math::vec3f{ 4.0F, 4.0F, 4.0F },
385 vn::math::vec3f{ 0.0F, 0.0F, 0.0F }
403 vn::protocol::uart::Scenario::SCENARIO_GPSMOVINGBASELINEDYNAMIC,
413 vn::math::vec3f{ 0, 0, 0 },
414 vn::math::vec3f{ 0, 0, 0 },
427 vn::protocol::uart::HsiMode::HSIMODE_RUN,
428 vn::protocol::uart::HsiOutput::HSIOUTPUT_USEONBOARD,
441 vn::math::vec3f{ 1.0F, 0.0F, 1.8F },
442 vn::math::vec3f{ 0.0F, 0.0F, -9.793746F }
454 vn::math::vec3d{ 0, 0, 0 }
466 vn::protocol::uart::VelocityCompensationMode::VELOCITYCOMPENSATIONMODE_BODYMEASUREMENT,
486 [](
VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; };
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
The class is responsible for all time-related tasks.
Abstract Uart Sensor Class.
Binary Outputs from VectorNav Sensors.
Abstract IMU Class.
Definition Imu.hpp:24
The class is responsible for all time-related tasks.
Definition InsTime.hpp:668
Abstract Uart Sensor Class.
Definition UartSensor.hpp:26
File Reader for Vector Nav log files.
Definition VectorNavFile.hpp:34
Vector Nav Sensor Class.
Definition VectorNavSensor.hpp:44
static constexpr size_t OUTPUT_PORT_INDEX_ASCII_OUTPUT
Flow (StringObs)
Definition VectorNavSensor.hpp:90
struct NAV::VectorNavSensor::@4 _gnssTimeCounter
Last received GNSS time.
std::array< vn::sensors::BinaryOutputRegister, 3 > _binaryOutputRegister
Binary Output Register 1 - 3.
Definition VectorNavSensor.hpp:236
vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister
Magnetometer Calibration Control.
Definition VectorNavSensor.hpp:426
VectorNavSensor(VectorNavSensor &&)=delete
Move constructor.
std::array< uint64_t, 3 > _lastMessageTimeSinceStartup
Stores the time of the last received message.
Definition VectorNavSensor.hpp:138
vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister
VPE Accelerometer Basic Tuning.
Definition VectorNavSensor.hpp:372
json save() const override
Saves the node into a json object.
vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister
Magnetic and Gravity Reference Vectors.
Definition VectorNavSensor.hpp:440
static constexpr std::array _possibleAsyncDataOutputFrequency
Possible values for the Async Data Output Frequency Register.
Definition VectorNavSensor.hpp:157
int _asyncDataOutputFrequencySelected
Selected Frequency of the Async Ascii Output in the GUI.
Definition VectorNavSensor.hpp:163
std::array< InsTime, 3 > _lastMessageTime
Stores the time of the last received message.
Definition VectorNavSensor.hpp:135
static const std::array< BinaryGroupData, 10 > _binaryGroupTime
Binary group 1 contains a wide assortment of commonly used data required for most applications.
Definition VectorNavSensor.hpp:505
vn::math::vec3f _filterStartupGyroBias
Filter Startup Gyro Bias.
Definition VectorNavSensor.hpp:392
std::string type() const override
String representation of the Class Type.
VectorNavSensor & operator=(VectorNavSensor &&)=delete
Move assignment operator.
VectorNavModel _sensorModel
The sensor model which is selected in the GUI.
Definition VectorNavSensor.hpp:120
bool _coupleImuRateOutput
Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor)
Definition VectorNavSensor.hpp:192
static void mergeVectorNavBinaryObservations(const std::shared_ptr< VectorNavBinaryOutput > &target, const std::shared_ptr< VectorNavBinaryOutput > &source)
Merges the content of the two observations into one.
static std::string typeStatic()
String representation of the Class Type.
BinaryRegisterMerge
Possible Merge combinations between the binary output registers.
Definition VectorNavSensor.hpp:216
@ None
Do not merge any outputs.
@ Output1_Output2
Merge Output 1 and 2.
@ Output2_Output3
Merge Output 2 and 3.
@ Output1_Output3
Merge Output 1 and 3.
static const std::array< BinaryGroupData, 11 > _binaryGroupIMU
Binary group 3 provides all outputs which are dependent upon the measurements collected from the onbo...
Definition VectorNavSensor.hpp:509
vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister
Delta Theta and Delta Velocity Configuration.
Definition VectorNavSensor.hpp:305
std::shared_ptr< VectorNavBinaryOutput > _binaryOutputRegisterMergeObservation
First observation received, which should be merged together.
Definition VectorNavSensor.hpp:227
void guiConfig() override
ImGui config window which is shown on double click.
vn::sensors::VnSensor _vs
VnSensor Object.
Definition VectorNavSensor.hpp:123
std::string _connectedSensorPort
Connected sensor port.
Definition VectorNavSensor.hpp:126
~VectorNavSensor() override
Destructor.
ScrollingBuffer< std::string > _asciiOutputBuffer
Buffer to store Ascii Output Messages.
Definition VectorNavSensor.hpp:169
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::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister
VPE Gyro Basic Tuning.
Definition VectorNavSensor.hpp:382
std::array< size_t, 3 > _binaryOutputSelectedFrequency
Selected Frequency of the Binary Outputs in the GUI.
Definition VectorNavSensor.hpp:270
static const std::array< BinaryGroupData, 9 > _binaryGroupAttitude
Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solutio...
Definition VectorNavSensor.hpp:525
vn::math::mat3f _referenceFrameRotationMatrix
Reference Frame Rotation.
Definition VectorNavSensor.hpp:280
vn::protocol::uart::AsciiAsync _asyncDataOutputType
Async Data Output Type Register.
Definition VectorNavSensor.hpp:153
vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister
IMU Filtering Configuration.
Definition VectorNavSensor.hpp:288
vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister
GNSS Compass Baseline.
Definition VectorNavSensor.hpp:338
vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister
Startup Filter Bias Estimate.
Definition VectorNavSensor.hpp:412
uint64_t timeSinceStartup
Time since startup when the GNSS time was received.
Definition VectorNavSensor.hpp:144
vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister
GNSS Configuration.
Definition VectorNavSensor.hpp:318
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.
Definition VectorNavSensor.hpp:229
static void coupleImuFilterRates(NAV::VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &binaryField)
Updates the ImuFilter's rate when pressing the checkbox button.
VectorNavModel
VectorNav Model enumeration.
Definition VectorNavSensor.hpp:111
@ VN310
VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass)
InsTime lastGnssTime
Last GNSS time received.
Definition VectorNavSensor.hpp:143
vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister
VPE Magnetometer Basic Tuning.
Definition VectorNavSensor.hpp:362
bool initialize() override
Initialize the node.
int _asciiOutputBufferSize
Max size of the Ascii Output.
Definition VectorNavSensor.hpp:166
VectorNavSensor(const VectorNavSensor &)=delete
Copy constructor.
vn::math::vec3f _gpsAntennaOffset
GNSS Antenna A Offset.
Definition VectorNavSensor.hpp:329
static constexpr double IMU_DEFAULT_FREQUENCY
Internal Frequency of the Sensor.
Definition VectorNavSensor.hpp:129
static std::string category()
String representation of the Class Category.
vn::sensors::SynchronizationControlRegister _synchronizationControlRegister
Synchronization Control.
Definition VectorNavSensor.hpp:175
vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister
VPE Basic Control.
Definition VectorNavSensor.hpp:351
void deinitialize() override
Deinitialize the node.
vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister
Communication Protocol Control.
Definition VectorNavSensor.hpp:204
TimeSync _timeSyncOut
Time synchronization for master sensors.
Definition VectorNavSensor.hpp:186
uint32_t _asyncDataOutputFrequency
Async Data Output Frequency Register.
Definition VectorNavSensor.hpp:161
BinaryRegisterMerge _binaryOutputRegisterMerge
Merge binary output registers together. This has to be done because VectorNav sensors have a buffer o...
Definition VectorNavSensor.hpp:224
VectorNavSensor & operator=(const VectorNavSensor &)=delete
Copy assignment operator.
vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister
Reference Vector Configuration.
Definition VectorNavSensor.hpp:449
bool _syncInPin
Show the SyncIn Pin.
Definition VectorNavSensor.hpp:189
static const std::array< BinaryGroupData, 11 > _binaryGroupINS
Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution...
Definition VectorNavSensor.hpp:530
vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300
INS Basic Configuration.
Definition VectorNavSensor.hpp:402
std::pair< std::vector< uint16_t >, std::vector< std::string > > _dividerFrequency
First: List of RateDividers, Second: List of Matching Frequencies.
Definition VectorNavSensor.hpp:132
bool resetNode() override
Resets the node. It is guaranteed that the node is initialized when this is called.
vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister
Velocity Compensation Control.
Definition VectorNavSensor.hpp:465
static const std::array< BinaryGroupData, 16 > _binaryGroupGNSS
Binary group 4 provides all outputs which are dependent upon the measurements collected from the prim...
Definition VectorNavSensor.hpp:519
Needed data to display a binary group in the GUI.
Definition VectorNavSensor.hpp:477
void(* toggleFields)(VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &)
Function to toggle other bits depending on the status.
Definition VectorNavSensor.hpp:488
int flagsValue
Enum value of the output.
Definition VectorNavSensor.hpp:481
void(* tooltip)()
Function providing a tooltip.
Definition VectorNavSensor.hpp:483
const char * name
Name of the output.
Definition VectorNavSensor.hpp:479
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)
Definition VectorNavSensor.hpp:485
Information needed to sync Master/Slave sensors.
Definition VectorNavSensor.hpp:48
InsTime ppsTime
Time of the last message with GNSS Time available (or empty otherwise)
Definition VectorNavSensor.hpp:49
uint32_t syncOutCnt
The number of SyncOut trigger events that have occurred.
Definition VectorNavSensor.hpp:50