VectorNav C++ Library
Functions
Register Access Methods

This group of methods provide access to read and write to the sensor's registers. More...

Functions

BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput1 ()
 Reads the Binary Output 1 register. More...
 
void vn::sensors::VnSensor::writeBinaryOutput1 (BinaryOutputRegister &fields, bool waitForReply=true)
 Writes to the Binary Output 1 register. More...
 
BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput2 ()
 Reads the Binary Output 2 register. More...
 
void vn::sensors::VnSensor::writeBinaryOutput2 (BinaryOutputRegister &fields, bool waitForReply=true)
 Writes to the Binary Output 2 register. More...
 
BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput3 ()
 Reads the Binary Output 3 register. More...
 
void vn::sensors::VnSensor::writeBinaryOutput3 (BinaryOutputRegister &fields, bool waitForReply=true)
 Writes to the Binary Output 3 register. More...
 
uint32_t vn::sensors::VnSensor::readSerialBaudRate (uint8_t port)
 Reads the Serial Baud Rate register for the specified port. More...
 
void vn::sensors::VnSensor::writeSerialBaudRate (const uint32_t &baudrate, uint8_t port, bool waitForReply=true)
 Writes to the Serial Baud Rate register for the specified port. More...
 
protocol::uart::AsciiAsync vn::sensors::VnSensor::readAsyncDataOutputType (uint8_t port)
 Reads the Async Data Output Type register. More...
 
void vn::sensors::VnSensor::writeAsyncDataOutputType (protocol::uart::AsciiAsync ador, uint8_t port, bool waitForReply=true)
 Writes to the Async Data Output Type register. More...
 
uint32_t vn::sensors::VnSensor::readAsyncDataOutputFrequency (uint8_t port)
 Reads the Async Data Output Frequency register. More...
 
void vn::sensors::VnSensor::writeAsyncDataOutputFrequency (const uint32_t &adof, uint8_t port, bool waitForReply=true)
 Writes to the Async Data Output Frequency register. More...
 
InsBasicConfigurationRegisterVn200 vn::sensors::VnSensor::readInsBasicConfigurationVn200 ()
 Reads the INS Basic Configuration register for a VN-200 sensor. More...
 
void vn::sensors::VnSensor::writeInsBasicConfigurationVn200 (InsBasicConfigurationRegisterVn200 &fields, bool waitForReply=true)
 Writes to the INS Basic Configuration register for a VN-200 sensor. More...
 
void vn::sensors::VnSensor::writeInsBasicConfigurationVn200 (protocol::uart::Scenario scenario, const uint8_t &ahrsAiding, bool waitForReply=true)
 Writes to the INS Basic Configuration register for a VN-200 sensor. More...
 
InsBasicConfigurationRegisterVn300 vn::sensors::VnSensor::readInsBasicConfigurationVn300 ()
 Reads the INS Basic Configuration register for a VN-300 sensor. More...
 
void vn::sensors::VnSensor::writeInsBasicConfigurationVn300 (InsBasicConfigurationRegisterVn300 &fields, bool waitForReply=true)
 Writes to the INS Basic Configuration register for a VN-300 sensor. More...
 
void vn::sensors::VnSensor::writeInsBasicConfigurationVn300 (protocol::uart::Scenario scenario, const uint8_t &ahrsAiding, const uint8_t &estBaseline, bool waitForReply=true)
 Writes to the INS Basic Configuration register for a VN-300 sensor. More...
 
std::string vn::sensors::VnSensor::readUserTag ()
 Reads the User Tag register. More...
 
void vn::sensors::VnSensor::writeUserTag (const std::string &tag, bool waitForReply=true)
 Writes to the User Tag register. More...
 
std::string vn::sensors::VnSensor::readModelNumber ()
 Reads the Model Number register. More...
 
uint32_t vn::sensors::VnSensor::readHardwareRevision ()
 Reads the Hardware Revision register. More...
 
uint32_t vn::sensors::VnSensor::readSerialNumber ()
 Reads the Serial Number register. More...
 
std::string vn::sensors::VnSensor::readFirmwareVersion ()
 Reads the Firmware Version register. More...
 
uint32_t vn::sensors::VnSensor::readSerialBaudRate ()
 Reads the Serial Baud Rate register. More...
 
void vn::sensors::VnSensor::writeSerialBaudRate (const uint32_t &baudrate, bool waitForReply=true)
 Writes to the Serial Baud Rate register. More...
 
protocol::uart::AsciiAsync vn::sensors::VnSensor::readAsyncDataOutputType ()
 Reads the Async Data Output Type register. More...
 
void vn::sensors::VnSensor::writeAsyncDataOutputType (protocol::uart::AsciiAsync ador, bool waitForReply=true)
 Writes to the Async Data Output Type register. More...
 
uint32_t vn::sensors::VnSensor::readAsyncDataOutputFrequency ()
 Reads the Async Data Output Frequency register. More...
 
void vn::sensors::VnSensor::writeAsyncDataOutputFrequency (const uint32_t &adof, bool waitForReply=true)
 Writes to the Async Data Output Frequency register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readYawPitchRoll ()
 Reads the Yaw Pitch Roll register. More...
 
vn::math::vec4f vn::sensors::VnSensor::readAttitudeQuaternion ()
 Reads the Attitude Quaternion register. More...
 
QuaternionMagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readQuaternionMagneticAccelerationAndAngularRates ()
 Reads the Quaternion, Magnetic, Acceleration and Angular Rates register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readMagneticMeasurements ()
 Reads the Magnetic Measurements register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readAccelerationMeasurements ()
 Reads the Acceleration Measurements register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readAngularRateMeasurements ()
 Reads the Angular Rate Measurements register. More...
 
MagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readMagneticAccelerationAndAngularRates ()
 Reads the Magnetic, Acceleration and Angular Rates register. More...
 
MagneticAndGravityReferenceVectorsRegister vn::sensors::VnSensor::readMagneticAndGravityReferenceVectors ()
 Reads the Magnetic and Gravity Reference Vectors register. More...
 
void vn::sensors::VnSensor::writeMagneticAndGravityReferenceVectors (MagneticAndGravityReferenceVectorsRegister &fields, bool waitForReply=true)
 Writes to the Magnetic and Gravity Reference Vectors register. More...
 
void vn::sensors::VnSensor::writeMagneticAndGravityReferenceVectors (const vn::math::vec3f &magRef, const vn::math::vec3f &accRef, bool waitForReply=true)
 Writes to the Magnetic and Gravity Reference Vectors register. More...
 
FilterMeasurementsVarianceParametersRegister vn::sensors::VnSensor::readFilterMeasurementsVarianceParameters ()
 Reads the Filter Measurements Variance Parameters register. More...
 
void vn::sensors::VnSensor::writeFilterMeasurementsVarianceParameters (FilterMeasurementsVarianceParametersRegister &fields, bool waitForReply=true)
 Writes to the Filter Measurements Variance Parameters register. More...
 
void vn::sensors::VnSensor::writeFilterMeasurementsVarianceParameters (const float &angularWalkVariance, const vn::math::vec3f &angularRateVariance, const vn::math::vec3f &magneticVariance, const vn::math::vec3f &accelerationVariance, bool waitForReply=true)
 Writes to the Filter Measurements Variance Parameters register. More...
 
MagnetometerCompensationRegister vn::sensors::VnSensor::readMagnetometerCompensation ()
 Reads the Magnetometer Compensation register. More...
 
void vn::sensors::VnSensor::writeMagnetometerCompensation (MagnetometerCompensationRegister &fields, bool waitForReply=true)
 Writes to the Magnetometer Compensation register. More...
 
void vn::sensors::VnSensor::writeMagnetometerCompensation (const vn::math::mat3f &c, const vn::math::vec3f &b, bool waitForReply=true)
 Writes to the Magnetometer Compensation register. More...
 
FilterActiveTuningParametersRegister vn::sensors::VnSensor::readFilterActiveTuningParameters ()
 Reads the Filter Active Tuning Parameters register. More...
 
void vn::sensors::VnSensor::writeFilterActiveTuningParameters (FilterActiveTuningParametersRegister &fields, bool waitForReply=true)
 Writes to the Filter Active Tuning Parameters register. More...
 
void vn::sensors::VnSensor::writeFilterActiveTuningParameters (const float &magneticDisturbanceGain, const float &accelerationDisturbanceGain, const float &magneticDisturbanceMemory, const float &accelerationDisturbanceMemory, bool waitForReply=true)
 Writes to the Filter Active Tuning Parameters register. More...
 
AccelerationCompensationRegister vn::sensors::VnSensor::readAccelerationCompensation ()
 Reads the Acceleration Compensation register. More...
 
void vn::sensors::VnSensor::writeAccelerationCompensation (AccelerationCompensationRegister &fields, bool waitForReply=true)
 Writes to the Acceleration Compensation register. More...
 
void vn::sensors::VnSensor::writeAccelerationCompensation (const vn::math::mat3f &c, const vn::math::vec3f &b, bool waitForReply=true)
 Writes to the Acceleration Compensation register. More...
 
vn::math::mat3f vn::sensors::VnSensor::readReferenceFrameRotation ()
 Reads the Reference Frame Rotation register. More...
 
void vn::sensors::VnSensor::writeReferenceFrameRotation (const vn::math::mat3f &c, bool waitForReply=true)
 Writes to the Reference Frame Rotation register. More...
 
YawPitchRollMagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollMagneticAccelerationAndAngularRates ()
 Reads the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register. More...
 
CommunicationProtocolControlRegister vn::sensors::VnSensor::readCommunicationProtocolControl ()
 Reads the Communication Protocol Control register. More...
 
void vn::sensors::VnSensor::writeCommunicationProtocolControl (CommunicationProtocolControlRegister &fields, bool waitForReply=true)
 Writes to the Communication Protocol Control register. More...
 
void vn::sensors::VnSensor::writeCommunicationProtocolControl (protocol::uart::CountMode serialCount, protocol::uart::StatusMode serialStatus, protocol::uart::CountMode spiCount, protocol::uart::StatusMode spiStatus, protocol::uart::ChecksumMode serialChecksum, protocol::uart::ChecksumMode spiChecksum, protocol::uart::ErrorMode errorMode, bool waitForReply=true)
 Writes to the Communication Protocol Control register. More...
 
SynchronizationControlRegister vn::sensors::VnSensor::readSynchronizationControl ()
 Reads the Synchronization Control register. More...
 
void vn::sensors::VnSensor::writeSynchronizationControl (SynchronizationControlRegister &fields, bool waitForReply=true)
 Writes to the Synchronization Control register. More...
 
void vn::sensors::VnSensor::writeSynchronizationControl (protocol::uart::SyncInMode syncInMode, protocol::uart::SyncInEdge syncInEdge, const uint16_t &syncInSkipFactor, protocol::uart::SyncOutMode syncOutMode, protocol::uart::SyncOutPolarity syncOutPolarity, const uint16_t &syncOutSkipFactor, const uint32_t &syncOutPulseWidth, bool waitForReply=true)
 Writes to the Synchronization Control register. More...
 
SynchronizationStatusRegister vn::sensors::VnSensor::readSynchronizationStatus ()
 Reads the Synchronization Status register. More...
 
void vn::sensors::VnSensor::writeSynchronizationStatus (SynchronizationStatusRegister &fields, bool waitForReply=true)
 Writes to the Synchronization Status register. More...
 
void vn::sensors::VnSensor::writeSynchronizationStatus (const uint32_t &syncInCount, const uint32_t &syncInTime, const uint32_t &syncOutCount, bool waitForReply=true)
 Writes to the Synchronization Status register. More...
 
FilterBasicControlRegister vn::sensors::VnSensor::readFilterBasicControl ()
 Reads the Filter Basic Control register. More...
 
void vn::sensors::VnSensor::writeFilterBasicControl (FilterBasicControlRegister &fields, bool waitForReply=true)
 Writes to the Filter Basic Control register. More...
 
void vn::sensors::VnSensor::writeFilterBasicControl (protocol::uart::MagneticMode magMode, protocol::uart::ExternalSensorMode extMagMode, protocol::uart::ExternalSensorMode extAccMode, protocol::uart::ExternalSensorMode extGyroMode, const vn::math::vec3f &gyroLimit, bool waitForReply=true)
 Writes to the Filter Basic Control register. More...
 
VpeBasicControlRegister vn::sensors::VnSensor::readVpeBasicControl ()
 Reads the VPE Basic Control register. More...
 
void vn::sensors::VnSensor::writeVpeBasicControl (VpeBasicControlRegister &fields, bool waitForReply=true)
 Writes to the VPE Basic Control register. More...
 
void vn::sensors::VnSensor::writeVpeBasicControl (protocol::uart::VpeEnable enable, protocol::uart::HeadingMode headingMode, protocol::uart::VpeMode filteringMode, protocol::uart::VpeMode tuningMode, bool waitForReply=true)
 Writes to the VPE Basic Control register. More...
 
VpeMagnetometerBasicTuningRegister vn::sensors::VnSensor::readVpeMagnetometerBasicTuning ()
 Reads the VPE Magnetometer Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeMagnetometerBasicTuning (VpeMagnetometerBasicTuningRegister &fields, bool waitForReply=true)
 Writes to the VPE Magnetometer Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeMagnetometerBasicTuning (const vn::math::vec3f &baseTuning, const vn::math::vec3f &adaptiveTuning, const vn::math::vec3f &adaptiveFiltering, bool waitForReply=true)
 Writes to the VPE Magnetometer Basic Tuning register. More...
 
VpeMagnetometerAdvancedTuningRegister vn::sensors::VnSensor::readVpeMagnetometerAdvancedTuning ()
 Reads the VPE Magnetometer Advanced Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeMagnetometerAdvancedTuning (VpeMagnetometerAdvancedTuningRegister &fields, bool waitForReply=true)
 Writes to the VPE Magnetometer Advanced Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeMagnetometerAdvancedTuning (const vn::math::vec3f &minFiltering, const vn::math::vec3f &maxFiltering, const float &maxAdaptRate, const float &disturbanceWindow, const float &maxTuning, bool waitForReply=true)
 Writes to the VPE Magnetometer Advanced Tuning register. More...
 
VpeAccelerometerBasicTuningRegister vn::sensors::VnSensor::readVpeAccelerometerBasicTuning ()
 Reads the VPE Accelerometer Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeAccelerometerBasicTuning (VpeAccelerometerBasicTuningRegister &fields, bool waitForReply=true)
 Writes to the VPE Accelerometer Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeAccelerometerBasicTuning (const vn::math::vec3f &baseTuning, const vn::math::vec3f &adaptiveTuning, const vn::math::vec3f &adaptiveFiltering, bool waitForReply=true)
 Writes to the VPE Accelerometer Basic Tuning register. More...
 
VpeAccelerometerAdvancedTuningRegister vn::sensors::VnSensor::readVpeAccelerometerAdvancedTuning ()
 Reads the VPE Accelerometer Advanced Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeAccelerometerAdvancedTuning (VpeAccelerometerAdvancedTuningRegister &fields, bool waitForReply=true)
 Writes to the VPE Accelerometer Advanced Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeAccelerometerAdvancedTuning (const vn::math::vec3f &minFiltering, const vn::math::vec3f &maxFiltering, const float &maxAdaptRate, const float &disturbanceWindow, const float &maxTuning, bool waitForReply=true)
 Writes to the VPE Accelerometer Advanced Tuning register. More...
 
VpeGyroBasicTuningRegister vn::sensors::VnSensor::readVpeGyroBasicTuning ()
 Reads the VPE Gyro Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeGyroBasicTuning (VpeGyroBasicTuningRegister &fields, bool waitForReply=true)
 Writes to the VPE Gyro Basic Tuning register. More...
 
void vn::sensors::VnSensor::writeVpeGyroBasicTuning (const vn::math::vec3f &angularWalkVariance, const vn::math::vec3f &baseTuning, const vn::math::vec3f &adaptiveTuning, bool waitForReply=true)
 Writes to the VPE Gyro Basic Tuning register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readFilterStartupGyroBias ()
 Reads the Filter Startup Gyro Bias register. More...
 
void vn::sensors::VnSensor::writeFilterStartupGyroBias (const vn::math::vec3f &bias, bool waitForReply=true)
 Writes to the Filter Startup Gyro Bias register. More...
 
MagnetometerCalibrationControlRegister vn::sensors::VnSensor::readMagnetometerCalibrationControl ()
 Reads the Magnetometer Calibration Control register. More...
 
void vn::sensors::VnSensor::writeMagnetometerCalibrationControl (MagnetometerCalibrationControlRegister &fields, bool waitForReply=true)
 Writes to the Magnetometer Calibration Control register. More...
 
void vn::sensors::VnSensor::writeMagnetometerCalibrationControl (protocol::uart::HsiMode hsiMode, protocol::uart::HsiOutput hsiOutput, const uint8_t &convergeRate, bool waitForReply=true)
 Writes to the Magnetometer Calibration Control register. More...
 
CalculatedMagnetometerCalibrationRegister vn::sensors::VnSensor::readCalculatedMagnetometerCalibration ()
 Reads the Calculated Magnetometer Calibration register. More...
 
float vn::sensors::VnSensor::readIndoorHeadingModeControl ()
 Reads the Indoor Heading Mode Control register. More...
 
void vn::sensors::VnSensor::writeIndoorHeadingModeControl (const float &maxRateError, bool waitForReply=true)
 Writes to the Indoor Heading Mode Control register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readVelocityCompensationMeasurement ()
 Reads the Velocity Compensation Measurement register. More...
 
void vn::sensors::VnSensor::writeVelocityCompensationMeasurement (const vn::math::vec3f &velocity, bool waitForReply=true)
 Writes to the Velocity Compensation Measurement register. More...
 
VelocityCompensationControlRegister vn::sensors::VnSensor::readVelocityCompensationControl ()
 Reads the Velocity Compensation Control register. More...
 
void vn::sensors::VnSensor::writeVelocityCompensationControl (VelocityCompensationControlRegister &fields, bool waitForReply=true)
 Writes to the Velocity Compensation Control register. More...
 
void vn::sensors::VnSensor::writeVelocityCompensationControl (protocol::uart::VelocityCompensationMode mode, const float &velocityTuning, const float &rateTuning, bool waitForReply=true)
 Writes to the Velocity Compensation Control register. More...
 
VelocityCompensationStatusRegister vn::sensors::VnSensor::readVelocityCompensationStatus ()
 Reads the Velocity Compensation Status register. More...
 
ImuMeasurementsRegister vn::sensors::VnSensor::readImuMeasurements ()
 Reads the IMU Measurements register. More...
 
GpsConfigurationRegister vn::sensors::VnSensor::readGpsConfiguration ()
 Reads the GPS Configuration register. More...
 
void vn::sensors::VnSensor::writeGpsConfiguration (GpsConfigurationRegister &fields, bool waitForReply=true)
 Writes to the GPS Configuration register. More...
 
void vn::sensors::VnSensor::writeGpsConfiguration (protocol::uart::GpsMode mode, protocol::uart::PpsSource ppsSource, bool waitForReply=true)
 Writes to the GPS Configuration register. More...
 
vn::math::vec3f vn::sensors::VnSensor::readGpsAntennaOffset ()
 Reads the GPS Antenna Offset register. More...
 
void vn::sensors::VnSensor::writeGpsAntennaOffset (const vn::math::vec3f &position, bool waitForReply=true)
 Writes to the GPS Antenna Offset register. More...
 
GpsSolutionLlaRegister vn::sensors::VnSensor::readGpsSolutionLla ()
 Reads the GPS Solution - LLA register. More...
 
GpsSolutionEcefRegister vn::sensors::VnSensor::readGpsSolutionEcef ()
 Reads the GPS Solution - ECEF register. More...
 
InsSolutionLlaRegister vn::sensors::VnSensor::readInsSolutionLla ()
 Reads the INS Solution - LLA register. More...
 
InsSolutionEcefRegister vn::sensors::VnSensor::readInsSolutionEcef ()
 Reads the INS Solution - ECEF register. More...
 
InsAdvancedConfigurationRegister vn::sensors::VnSensor::readInsAdvancedConfiguration ()
 Reads the INS Advanced Configuration register. More...
 
void vn::sensors::VnSensor::writeInsAdvancedConfiguration (InsAdvancedConfigurationRegister &fields, bool waitForReply=true)
 Writes to the INS Advanced Configuration register. More...
 
void vn::sensors::VnSensor::writeInsAdvancedConfiguration (const uint8_t &useMag, const uint8_t &usePres, const uint8_t &posAtt, const uint8_t &velAtt, const uint8_t &velBias, protocol::uart::FoamInit useFoam, const uint8_t &gpsCovType, const uint8_t &velCount, const float &velInit, const float &moveOrigin, const float &gpsTimeout, const float &deltaLimitPos, const float &deltaLimitVel, const float &minPosUncertainty, const float &minVelUncertainty, bool waitForReply=true)
 Writes to the INS Advanced Configuration register. More...
 
InsStateLlaRegister vn::sensors::VnSensor::readInsStateLla ()
 Reads the INS State - LLA register. More...
 
InsStateEcefRegister vn::sensors::VnSensor::readInsStateEcef ()
 Reads the INS State - ECEF register. More...
 
StartupFilterBiasEstimateRegister vn::sensors::VnSensor::readStartupFilterBiasEstimate ()
 Reads the Startup Filter Bias Estimate register. More...
 
void vn::sensors::VnSensor::writeStartupFilterBiasEstimate (StartupFilterBiasEstimateRegister &fields, bool waitForReply=true)
 Writes to the Startup Filter Bias Estimate register. More...
 
void vn::sensors::VnSensor::writeStartupFilterBiasEstimate (const vn::math::vec3f &gyroBias, const vn::math::vec3f &accelBias, const float &pressureBias, bool waitForReply=true)
 Writes to the Startup Filter Bias Estimate register. More...
 
DeltaThetaAndDeltaVelocityRegister vn::sensors::VnSensor::readDeltaThetaAndDeltaVelocity ()
 Reads the Delta Theta and Delta Velocity register. More...
 
DeltaThetaAndDeltaVelocityConfigurationRegister vn::sensors::VnSensor::readDeltaThetaAndDeltaVelocityConfiguration ()
 Reads the Delta Theta and Delta Velocity Configuration register. More...
 
void vn::sensors::VnSensor::writeDeltaThetaAndDeltaVelocityConfiguration (DeltaThetaAndDeltaVelocityConfigurationRegister &fields, bool waitForReply=true)
 Writes to the Delta Theta and Delta Velocity Configuration register. More...
 
void vn::sensors::VnSensor::writeDeltaThetaAndDeltaVelocityConfiguration (protocol::uart::IntegrationFrame integrationFrame, protocol::uart::CompensationMode gyroCompensation, protocol::uart::CompensationMode accelCompensation, bool waitForReply=true)
 Writes to the Delta Theta and Delta Velocity Configuration register. More...
 
ReferenceVectorConfigurationRegister vn::sensors::VnSensor::readReferenceVectorConfiguration ()
 Reads the Reference Vector Configuration register. More...
 
void vn::sensors::VnSensor::writeReferenceVectorConfiguration (ReferenceVectorConfigurationRegister &fields, bool waitForReply=true)
 Writes to the Reference Vector Configuration register. More...
 
void vn::sensors::VnSensor::writeReferenceVectorConfiguration (const uint8_t &useMagModel, const uint8_t &useGravityModel, const uint32_t &recalcThreshold, const float &year, const vn::math::vec3d &position, bool waitForReply=true)
 Writes to the Reference Vector Configuration register. More...
 
GyroCompensationRegister vn::sensors::VnSensor::readGyroCompensation ()
 Reads the Gyro Compensation register. More...
 
void vn::sensors::VnSensor::writeGyroCompensation (GyroCompensationRegister &fields, bool waitForReply=true)
 Writes to the Gyro Compensation register. More...
 
void vn::sensors::VnSensor::writeGyroCompensation (const vn::math::mat3f &c, const vn::math::vec3f &b, bool waitForReply=true)
 Writes to the Gyro Compensation register. More...
 
ImuFilteringConfigurationRegister vn::sensors::VnSensor::readImuFilteringConfiguration ()
 Reads the IMU Filtering Configuration register. More...
 
void vn::sensors::VnSensor::writeImuFilteringConfiguration (ImuFilteringConfigurationRegister &fields, bool waitForReply=true)
 Writes to the IMU Filtering Configuration register. More...
 
void vn::sensors::VnSensor::writeImuFilteringConfiguration (const uint16_t &magWindowSize, const uint16_t &accelWindowSize, const uint16_t &gyroWindowSize, const uint16_t &tempWindowSize, const uint16_t &presWindowSize, protocol::uart::FilterMode magFilterMode, protocol::uart::FilterMode accelFilterMode, protocol::uart::FilterMode gyroFilterMode, protocol::uart::FilterMode tempFilterMode, protocol::uart::FilterMode presFilterMode, bool waitForReply=true)
 Writes to the IMU Filtering Configuration register. More...
 
GpsCompassBaselineRegister vn::sensors::VnSensor::readGpsCompassBaseline ()
 Reads the GPS Compass Baseline register. More...
 
void vn::sensors::VnSensor::writeGpsCompassBaseline (GpsCompassBaselineRegister &fields, bool waitForReply=true)
 Writes to the GPS Compass Baseline register. More...
 
void vn::sensors::VnSensor::writeGpsCompassBaseline (const vn::math::vec3f &position, const vn::math::vec3f &uncertainty, bool waitForReply=true)
 Writes to the GPS Compass Baseline register. More...
 
GpsCompassEstimatedBaselineRegister vn::sensors::VnSensor::readGpsCompassEstimatedBaseline ()
 Reads the GPS Compass Estimated Baseline register. More...
 
ImuRateConfigurationRegister vn::sensors::VnSensor::readImuRateConfiguration ()
 Reads the IMU Rate Configuration register. More...
 
void vn::sensors::VnSensor::writeImuRateConfiguration (ImuRateConfigurationRegister &fields, bool waitForReply=true)
 Writes to the IMU Rate Configuration register. More...
 
void vn::sensors::VnSensor::writeImuRateConfiguration (const uint16_t &imuRate, const uint16_t &navDivisor, const float &filterTargetRate, const float &filterMinRate, bool waitForReply=true)
 Writes to the IMU Rate Configuration register. More...
 
YawPitchRollTrueBodyAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollTrueBodyAccelerationAndAngularRates ()
 Reads the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register. More...
 
YawPitchRollTrueInertialAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollTrueInertialAccelerationAndAngularRates ()
 Reads the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates register. More...
 

Detailed Description

This group of methods provide access to read and write to the sensor's registers.

Function Documentation

AccelerationCompensationRegister vn::sensors::VnSensor::readAccelerationCompensation ( )

Reads the Acceleration Compensation register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readAccelerationMeasurements ( )

Reads the Acceleration Measurements register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readAngularRateMeasurements ( )

Reads the Angular Rate Measurements register.

Returns
The register's values.
uint32_t vn::sensors::VnSensor::readAsyncDataOutputFrequency ( uint8_t  port)

Reads the Async Data Output Frequency register.

Parameters
[in]portThe port number to read from.
Returns
The register's values.
Examples:
getting_started/main.cpp.
uint32_t vn::sensors::VnSensor::readAsyncDataOutputFrequency ( )

Reads the Async Data Output Frequency register.

Returns
The register's values.
protocol::uart::AsciiAsync vn::sensors::VnSensor::readAsyncDataOutputType ( uint8_t  port)

Reads the Async Data Output Type register.

Parameters
[in]portThe port number to read from.
Returns
The register's values.
Examples:
getting_started/main.cpp.
protocol::uart::AsciiAsync vn::sensors::VnSensor::readAsyncDataOutputType ( )

Reads the Async Data Output Type register.

Returns
The register's values.
vn::math::vec4f vn::sensors::VnSensor::readAttitudeQuaternion ( )

Reads the Attitude Quaternion register.

Returns
The register's values.
BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput1 ( )

Reads the Binary Output 1 register.

Returns
The register's values.
BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput2 ( )

Reads the Binary Output 2 register.

Returns
The register's values.
BinaryOutputRegister vn::sensors::VnSensor::readBinaryOutput3 ( )

Reads the Binary Output 3 register.

Returns
The register's values.
CalculatedMagnetometerCalibrationRegister vn::sensors::VnSensor::readCalculatedMagnetometerCalibration ( )

Reads the Calculated Magnetometer Calibration register.

Returns
The register's values.
CommunicationProtocolControlRegister vn::sensors::VnSensor::readCommunicationProtocolControl ( )

Reads the Communication Protocol Control register.

Returns
The register's values.
DeltaThetaAndDeltaVelocityRegister vn::sensors::VnSensor::readDeltaThetaAndDeltaVelocity ( )

Reads the Delta Theta and Delta Velocity register.

Returns
The register's values.
DeltaThetaAndDeltaVelocityConfigurationRegister vn::sensors::VnSensor::readDeltaThetaAndDeltaVelocityConfiguration ( )

Reads the Delta Theta and Delta Velocity Configuration register.

Returns
The register's values.
FilterActiveTuningParametersRegister vn::sensors::VnSensor::readFilterActiveTuningParameters ( )

Reads the Filter Active Tuning Parameters register.

Returns
The register's values.
FilterBasicControlRegister vn::sensors::VnSensor::readFilterBasicControl ( )

Reads the Filter Basic Control register.

Returns
The register's values.
FilterMeasurementsVarianceParametersRegister vn::sensors::VnSensor::readFilterMeasurementsVarianceParameters ( )

Reads the Filter Measurements Variance Parameters register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readFilterStartupGyroBias ( )

Reads the Filter Startup Gyro Bias register.

Returns
The register's values.
std::string vn::sensors::VnSensor::readFirmwareVersion ( )

Reads the Firmware Version register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readGpsAntennaOffset ( )

Reads the GPS Antenna Offset register.

Returns
The register's values.
GpsCompassBaselineRegister vn::sensors::VnSensor::readGpsCompassBaseline ( )

Reads the GPS Compass Baseline register.

Returns
The register's values.
GpsCompassEstimatedBaselineRegister vn::sensors::VnSensor::readGpsCompassEstimatedBaseline ( )

Reads the GPS Compass Estimated Baseline register.

Returns
The register's values.
GpsConfigurationRegister vn::sensors::VnSensor::readGpsConfiguration ( )

Reads the GPS Configuration register.

Returns
The register's values.
GpsSolutionEcefRegister vn::sensors::VnSensor::readGpsSolutionEcef ( )

Reads the GPS Solution - ECEF register.

Returns
The register's values.
GpsSolutionLlaRegister vn::sensors::VnSensor::readGpsSolutionLla ( )

Reads the GPS Solution - LLA register.

Returns
The register's values.
GyroCompensationRegister vn::sensors::VnSensor::readGyroCompensation ( )

Reads the Gyro Compensation register.

Returns
The register's values.
uint32_t vn::sensors::VnSensor::readHardwareRevision ( )

Reads the Hardware Revision register.

Returns
The register's values.
ImuFilteringConfigurationRegister vn::sensors::VnSensor::readImuFilteringConfiguration ( )

Reads the IMU Filtering Configuration register.

Returns
The register's values.
ImuMeasurementsRegister vn::sensors::VnSensor::readImuMeasurements ( )

Reads the IMU Measurements register.

Returns
The register's values.
ImuRateConfigurationRegister vn::sensors::VnSensor::readImuRateConfiguration ( )

Reads the IMU Rate Configuration register.

Returns
The register's values.
float vn::sensors::VnSensor::readIndoorHeadingModeControl ( )

Reads the Indoor Heading Mode Control register.

Returns
The register's values.
InsAdvancedConfigurationRegister vn::sensors::VnSensor::readInsAdvancedConfiguration ( )

Reads the INS Advanced Configuration register.

Returns
The register's values.
InsBasicConfigurationRegisterVn200 vn::sensors::VnSensor::readInsBasicConfigurationVn200 ( )

Reads the INS Basic Configuration register for a VN-200 sensor.

Returns
The register's values.
InsBasicConfigurationRegisterVn300 vn::sensors::VnSensor::readInsBasicConfigurationVn300 ( )

Reads the INS Basic Configuration register for a VN-300 sensor.

Returns
The register's values.
InsSolutionEcefRegister vn::sensors::VnSensor::readInsSolutionEcef ( )

Reads the INS Solution - ECEF register.

Returns
The register's values.
InsSolutionLlaRegister vn::sensors::VnSensor::readInsSolutionLla ( )

Reads the INS Solution - LLA register.

Returns
The register's values.
InsStateEcefRegister vn::sensors::VnSensor::readInsStateEcef ( )

Reads the INS State - ECEF register.

Returns
The register's values.
InsStateLlaRegister vn::sensors::VnSensor::readInsStateLla ( )

Reads the INS State - LLA register.

Returns
The register's values.
MagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readMagneticAccelerationAndAngularRates ( )

Reads the Magnetic, Acceleration and Angular Rates register.

Returns
The register's values.
MagneticAndGravityReferenceVectorsRegister vn::sensors::VnSensor::readMagneticAndGravityReferenceVectors ( )

Reads the Magnetic and Gravity Reference Vectors register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readMagneticMeasurements ( )

Reads the Magnetic Measurements register.

Returns
The register's values.
MagnetometerCalibrationControlRegister vn::sensors::VnSensor::readMagnetometerCalibrationControl ( )

Reads the Magnetometer Calibration Control register.

Returns
The register's values.
MagnetometerCompensationRegister vn::sensors::VnSensor::readMagnetometerCompensation ( )

Reads the Magnetometer Compensation register.

Returns
The register's values.
std::string vn::sensors::VnSensor::readModelNumber ( )

Reads the Model Number register.

Returns
The register's values.
Examples:
getting_started/main.cpp.
QuaternionMagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readQuaternionMagneticAccelerationAndAngularRates ( )

Reads the Quaternion, Magnetic, Acceleration and Angular Rates register.

Returns
The register's values.
vn::math::mat3f vn::sensors::VnSensor::readReferenceFrameRotation ( )

Reads the Reference Frame Rotation register.

Returns
The register's values.
ReferenceVectorConfigurationRegister vn::sensors::VnSensor::readReferenceVectorConfiguration ( )

Reads the Reference Vector Configuration register.

Returns
The register's values.
uint32_t vn::sensors::VnSensor::readSerialBaudRate ( uint8_t  port)

Reads the Serial Baud Rate register for the specified port.

Parameters
[in]portThe port number to read from.
Returns
The register's values.
uint32_t vn::sensors::VnSensor::readSerialBaudRate ( )

Reads the Serial Baud Rate register.

Returns
The register's values.
uint32_t vn::sensors::VnSensor::readSerialNumber ( )

Reads the Serial Number register.

Returns
The register's values.
StartupFilterBiasEstimateRegister vn::sensors::VnSensor::readStartupFilterBiasEstimate ( )

Reads the Startup Filter Bias Estimate register.

Returns
The register's values.
SynchronizationControlRegister vn::sensors::VnSensor::readSynchronizationControl ( )

Reads the Synchronization Control register.

Returns
The register's values.
SynchronizationStatusRegister vn::sensors::VnSensor::readSynchronizationStatus ( )

Reads the Synchronization Status register.

Returns
The register's values.
std::string vn::sensors::VnSensor::readUserTag ( )

Reads the User Tag register.

Returns
The register's values.
VelocityCompensationControlRegister vn::sensors::VnSensor::readVelocityCompensationControl ( )

Reads the Velocity Compensation Control register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readVelocityCompensationMeasurement ( )

Reads the Velocity Compensation Measurement register.

Returns
The register's values.
VelocityCompensationStatusRegister vn::sensors::VnSensor::readVelocityCompensationStatus ( )

Reads the Velocity Compensation Status register.

Returns
The register's values.
VpeAccelerometerAdvancedTuningRegister vn::sensors::VnSensor::readVpeAccelerometerAdvancedTuning ( )

Reads the VPE Accelerometer Advanced Tuning register.

Returns
The register's values.
VpeAccelerometerBasicTuningRegister vn::sensors::VnSensor::readVpeAccelerometerBasicTuning ( )

Reads the VPE Accelerometer Basic Tuning register.

Returns
The register's values.
VpeBasicControlRegister vn::sensors::VnSensor::readVpeBasicControl ( )

Reads the VPE Basic Control register.

Returns
The register's values.
Examples:
getting_started/main.cpp.
VpeGyroBasicTuningRegister vn::sensors::VnSensor::readVpeGyroBasicTuning ( )

Reads the VPE Gyro Basic Tuning register.

Returns
The register's values.
VpeMagnetometerAdvancedTuningRegister vn::sensors::VnSensor::readVpeMagnetometerAdvancedTuning ( )

Reads the VPE Magnetometer Advanced Tuning register.

Returns
The register's values.
VpeMagnetometerBasicTuningRegister vn::sensors::VnSensor::readVpeMagnetometerBasicTuning ( )

Reads the VPE Magnetometer Basic Tuning register.

Returns
The register's values.
vn::math::vec3f vn::sensors::VnSensor::readYawPitchRoll ( )

Reads the Yaw Pitch Roll register.

Returns
The register's values.
Examples:
getting_started/main.cpp.
YawPitchRollMagneticAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollMagneticAccelerationAndAngularRates ( )

Reads the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register.

Returns
The register's values.
Examples:
getting_started/main.cpp.
YawPitchRollTrueBodyAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollTrueBodyAccelerationAndAngularRates ( )

Reads the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register.

Returns
The register's values.
YawPitchRollTrueInertialAccelerationAndAngularRatesRegister vn::sensors::VnSensor::readYawPitchRollTrueInertialAccelerationAndAngularRates ( )

Reads the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates register.

Returns
The register's values.
void vn::sensors::VnSensor::writeAccelerationCompensation ( AccelerationCompensationRegister fields,
bool  waitForReply = true 
)

Writes to the Acceleration Compensation register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeAccelerationCompensation ( const vn::math::mat3f c,
const vn::math::vec3f b,
bool  waitForReply = true 
)

Writes to the Acceleration Compensation register.

Parameters
[in]cValue for the C field.
[in]bValue for the B field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeAsyncDataOutputFrequency ( const uint32_t &  adof,
uint8_t  port,
bool  waitForReply = true 
)

Writes to the Async Data Output Frequency register.

Parameters
[in]adofThe register's ADOF field.
[in]portThe port number to write to.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
Examples:
getting_started/main.cpp.
void vn::sensors::VnSensor::writeAsyncDataOutputFrequency ( const uint32_t &  adof,
bool  waitForReply = true 
)

Writes to the Async Data Output Frequency register.

Parameters
[in]adofThe register's ADOF field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeAsyncDataOutputType ( protocol::uart::AsciiAsync  ador,
uint8_t  port,
bool  waitForReply = true 
)

Writes to the Async Data Output Type register.

Parameters
[in]adorThe register's ADOR field.
[in]portThe port number to write to.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
Examples:
ez_async_data/main.cpp, and getting_started/main.cpp.
void vn::sensors::VnSensor::writeAsyncDataOutputType ( protocol::uart::AsciiAsync  ador,
bool  waitForReply = true 
)

Writes to the Async Data Output Type register.

Parameters
[in]adorThe register's ADOR field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeBinaryOutput1 ( BinaryOutputRegister fields,
bool  waitForReply = true 
)

Writes to the Binary Output 1 register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
Examples:
getting_started/main.cpp.
void vn::sensors::VnSensor::writeBinaryOutput2 ( BinaryOutputRegister fields,
bool  waitForReply = true 
)

Writes to the Binary Output 2 register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeBinaryOutput3 ( BinaryOutputRegister fields,
bool  waitForReply = true 
)

Writes to the Binary Output 3 register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeCommunicationProtocolControl ( CommunicationProtocolControlRegister fields,
bool  waitForReply = true 
)

Writes to the Communication Protocol Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeCommunicationProtocolControl ( protocol::uart::CountMode  serialCount,
protocol::uart::StatusMode  serialStatus,
protocol::uart::CountMode  spiCount,
protocol::uart::StatusMode  spiStatus,
protocol::uart::ChecksumMode  serialChecksum,
protocol::uart::ChecksumMode  spiChecksum,
protocol::uart::ErrorMode  errorMode,
bool  waitForReply = true 
)

Writes to the Communication Protocol Control register.

Parameters
[in]serialCountValue for the SerialCount field.
[in]serialStatusValue for the SerialStatus field.
[in]spiCountValue for the SPICount field.
[in]spiStatusValue for the SPIStatus field.
[in]serialChecksumValue for the SerialChecksum field.
[in]spiChecksumValue for the SPIChecksum field.
[in]errorModeValue for the ErrorMode field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeDeltaThetaAndDeltaVelocityConfiguration ( DeltaThetaAndDeltaVelocityConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the Delta Theta and Delta Velocity Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeDeltaThetaAndDeltaVelocityConfiguration ( protocol::uart::IntegrationFrame  integrationFrame,
protocol::uart::CompensationMode  gyroCompensation,
protocol::uart::CompensationMode  accelCompensation,
bool  waitForReply = true 
)

Writes to the Delta Theta and Delta Velocity Configuration register.

Parameters
[in]integrationFrameValue for the IntegrationFrame field.
[in]gyroCompensationValue for the GyroCompensation field.
[in]accelCompensationValue for the AccelCompensation field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterActiveTuningParameters ( FilterActiveTuningParametersRegister fields,
bool  waitForReply = true 
)

Writes to the Filter Active Tuning Parameters register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterActiveTuningParameters ( const float &  magneticDisturbanceGain,
const float &  accelerationDisturbanceGain,
const float &  magneticDisturbanceMemory,
const float &  accelerationDisturbanceMemory,
bool  waitForReply = true 
)

Writes to the Filter Active Tuning Parameters register.

Parameters
[in]magneticDisturbanceGainValue for the Magnetic Disturbance Gain field.
[in]accelerationDisturbanceGainValue for the Acceleration Disturbance Gain field.
[in]magneticDisturbanceMemoryValue for the Magnetic Disturbance Memory field.
[in]accelerationDisturbanceMemoryValue for the Acceleration Disturbance Memory field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterBasicControl ( FilterBasicControlRegister fields,
bool  waitForReply = true 
)

Writes to the Filter Basic Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterBasicControl ( protocol::uart::MagneticMode  magMode,
protocol::uart::ExternalSensorMode  extMagMode,
protocol::uart::ExternalSensorMode  extAccMode,
protocol::uart::ExternalSensorMode  extGyroMode,
const vn::math::vec3f gyroLimit,
bool  waitForReply = true 
)

Writes to the Filter Basic Control register.

Parameters
[in]magModeValue for the MagMode field.
[in]extMagModeValue for the ExtMagMode field.
[in]extAccModeValue for the ExtAccMode field.
[in]extGyroModeValue for the ExtGyroMode field.
[in]gyroLimitValue for the GyroLimit field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterMeasurementsVarianceParameters ( FilterMeasurementsVarianceParametersRegister fields,
bool  waitForReply = true 
)

Writes to the Filter Measurements Variance Parameters register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterMeasurementsVarianceParameters ( const float &  angularWalkVariance,
const vn::math::vec3f angularRateVariance,
const vn::math::vec3f magneticVariance,
const vn::math::vec3f accelerationVariance,
bool  waitForReply = true 
)

Writes to the Filter Measurements Variance Parameters register.

Parameters
[in]angularWalkVarianceValue for the Angular Walk Variance field.
[in]angularRateVarianceValue for the Angular Rate Variance field.
[in]magneticVarianceValue for the Magnetic Variance field.
[in]accelerationVarianceValue for the Acceleration Variance field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeFilterStartupGyroBias ( const vn::math::vec3f bias,
bool  waitForReply = true 
)

Writes to the Filter Startup Gyro Bias register.

Parameters
[in]biasThe register's Bias field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGpsAntennaOffset ( const vn::math::vec3f position,
bool  waitForReply = true 
)

Writes to the GPS Antenna Offset register.

Parameters
[in]positionThe register's Position field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGpsCompassBaseline ( GpsCompassBaselineRegister fields,
bool  waitForReply = true 
)

Writes to the GPS Compass Baseline register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGpsCompassBaseline ( const vn::math::vec3f position,
const vn::math::vec3f uncertainty,
bool  waitForReply = true 
)

Writes to the GPS Compass Baseline register.

Parameters
[in]positionValue for the Position field.
[in]uncertaintyValue for the Uncertainty field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGpsConfiguration ( GpsConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the GPS Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGpsConfiguration ( protocol::uart::GpsMode  mode,
protocol::uart::PpsSource  ppsSource,
bool  waitForReply = true 
)

Writes to the GPS Configuration register.

Parameters
[in]modeValue for the Mode field.
[in]ppsSourceValue for the PpsSource field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGyroCompensation ( GyroCompensationRegister fields,
bool  waitForReply = true 
)

Writes to the Gyro Compensation register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeGyroCompensation ( const vn::math::mat3f c,
const vn::math::vec3f b,
bool  waitForReply = true 
)

Writes to the Gyro Compensation register.

Parameters
[in]cValue for the C field.
[in]bValue for the B field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeImuFilteringConfiguration ( ImuFilteringConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the IMU Filtering Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeImuFilteringConfiguration ( const uint16_t &  magWindowSize,
const uint16_t &  accelWindowSize,
const uint16_t &  gyroWindowSize,
const uint16_t &  tempWindowSize,
const uint16_t &  presWindowSize,
protocol::uart::FilterMode  magFilterMode,
protocol::uart::FilterMode  accelFilterMode,
protocol::uart::FilterMode  gyroFilterMode,
protocol::uart::FilterMode  tempFilterMode,
protocol::uart::FilterMode  presFilterMode,
bool  waitForReply = true 
)

Writes to the IMU Filtering Configuration register.

Parameters
[in]magWindowSizeValue for the MagWindowSize field.
[in]accelWindowSizeValue for the AccelWindowSize field.
[in]gyroWindowSizeValue for the GyroWindowSize field.
[in]tempWindowSizeValue for the TempWindowSize field.
[in]presWindowSizeValue for the PresWindowSize field.
[in]magFilterModeValue for the MagFilterMode field.
[in]accelFilterModeValue for the AccelFilterMode field.
[in]gyroFilterModeValue for the GyroFilterMode field.
[in]tempFilterModeValue for the TempFilterMode field.
[in]presFilterModeValue for the PresFilterMode field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeImuRateConfiguration ( ImuRateConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the IMU Rate Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeImuRateConfiguration ( const uint16_t &  imuRate,
const uint16_t &  navDivisor,
const float &  filterTargetRate,
const float &  filterMinRate,
bool  waitForReply = true 
)

Writes to the IMU Rate Configuration register.

Parameters
[in]imuRateValue for the imuRate field.
[in]navDivisorValue for the NavDivisor field.
[in]filterTargetRateValue for the filterTargetRate field.
[in]filterMinRateValue for the filterMinRate field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeIndoorHeadingModeControl ( const float &  maxRateError,
bool  waitForReply = true 
)

Writes to the Indoor Heading Mode Control register.

Parameters
[in]maxRateErrorThe register's Max Rate Error field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsAdvancedConfiguration ( InsAdvancedConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the INS Advanced Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsAdvancedConfiguration ( const uint8_t &  useMag,
const uint8_t &  usePres,
const uint8_t &  posAtt,
const uint8_t &  velAtt,
const uint8_t &  velBias,
protocol::uart::FoamInit  useFoam,
const uint8_t &  gpsCovType,
const uint8_t &  velCount,
const float &  velInit,
const float &  moveOrigin,
const float &  gpsTimeout,
const float &  deltaLimitPos,
const float &  deltaLimitVel,
const float &  minPosUncertainty,
const float &  minVelUncertainty,
bool  waitForReply = true 
)

Writes to the INS Advanced Configuration register.

Parameters
[in]useMagValue for the UseMag field.
[in]usePresValue for the UsePres field.
[in]posAttValue for the PosAtt field.
[in]velAttValue for the VelAtt field.
[in]velBiasValue for the VelBias field.
[in]useFoamValue for the UseFoam field.
[in]gpsCovTypeValue for the GPSCovType field.
[in]velCountValue for the VelCount field.
[in]velInitValue for the VelInit field.
[in]moveOriginValue for the MoveOrigin field.
[in]gpsTimeoutValue for the GPSTimeout field.
[in]deltaLimitPosValue for the DeltaLimitPos field.
[in]deltaLimitVelValue for the DeltaLimitVel field.
[in]minPosUncertaintyValue for the MinPosUncertainty field.
[in]minVelUncertaintyValue for the MinVelUncertainty field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsBasicConfigurationVn200 ( InsBasicConfigurationRegisterVn200 fields,
bool  waitForReply = true 
)

Writes to the INS Basic Configuration register for a VN-200 sensor.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsBasicConfigurationVn200 ( protocol::uart::Scenario  scenario,
const uint8_t &  ahrsAiding,
bool  waitForReply = true 
)

Writes to the INS Basic Configuration register for a VN-200 sensor.

Parameters
[in]scenarioValue for the Scenario field.
[in]ahrsAidingValue for the AhrsAiding field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsBasicConfigurationVn300 ( InsBasicConfigurationRegisterVn300 fields,
bool  waitForReply = true 
)

Writes to the INS Basic Configuration register for a VN-300 sensor.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeInsBasicConfigurationVn300 ( protocol::uart::Scenario  scenario,
const uint8_t &  ahrsAiding,
const uint8_t &  estBaseline,
bool  waitForReply = true 
)

Writes to the INS Basic Configuration register for a VN-300 sensor.

Parameters
[in]scenarioValue for the Scenario field.
[in]ahrsAidingValue for the AhrsAiding field.
[in]estBaselineValue for the EstBaseline field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagneticAndGravityReferenceVectors ( MagneticAndGravityReferenceVectorsRegister fields,
bool  waitForReply = true 
)

Writes to the Magnetic and Gravity Reference Vectors register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagneticAndGravityReferenceVectors ( const vn::math::vec3f magRef,
const vn::math::vec3f accRef,
bool  waitForReply = true 
)

Writes to the Magnetic and Gravity Reference Vectors register.

Parameters
[in]magRefValue for the MagRef field.
[in]accRefValue for the AccRef field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagnetometerCalibrationControl ( MagnetometerCalibrationControlRegister fields,
bool  waitForReply = true 
)

Writes to the Magnetometer Calibration Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagnetometerCalibrationControl ( protocol::uart::HsiMode  hsiMode,
protocol::uart::HsiOutput  hsiOutput,
const uint8_t &  convergeRate,
bool  waitForReply = true 
)

Writes to the Magnetometer Calibration Control register.

Parameters
[in]hsiModeValue for the HSIMode field.
[in]hsiOutputValue for the HSIOutput field.
[in]convergeRateValue for the ConvergeRate field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagnetometerCompensation ( MagnetometerCompensationRegister fields,
bool  waitForReply = true 
)

Writes to the Magnetometer Compensation register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeMagnetometerCompensation ( const vn::math::mat3f c,
const vn::math::vec3f b,
bool  waitForReply = true 
)

Writes to the Magnetometer Compensation register.

Parameters
[in]cValue for the C field.
[in]bValue for the B field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeReferenceFrameRotation ( const vn::math::mat3f c,
bool  waitForReply = true 
)

Writes to the Reference Frame Rotation register.

Parameters
[in]cThe register's C field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeReferenceVectorConfiguration ( ReferenceVectorConfigurationRegister fields,
bool  waitForReply = true 
)

Writes to the Reference Vector Configuration register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeReferenceVectorConfiguration ( const uint8_t &  useMagModel,
const uint8_t &  useGravityModel,
const uint32_t &  recalcThreshold,
const float &  year,
const vn::math::vec3d position,
bool  waitForReply = true 
)

Writes to the Reference Vector Configuration register.

Parameters
[in]useMagModelValue for the UseMagModel field.
[in]useGravityModelValue for the UseGravityModel field.
[in]recalcThresholdValue for the RecalcThreshold field.
[in]yearValue for the Year field.
[in]positionValue for the Position field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSerialBaudRate ( const uint32_t &  baudrate,
uint8_t  port,
bool  waitForReply = true 
)

Writes to the Serial Baud Rate register for the specified port.

Parameters
[in]baudrateThe register's Baud Rate field.
[in]portThe port number to write to.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSerialBaudRate ( const uint32_t &  baudrate,
bool  waitForReply = true 
)

Writes to the Serial Baud Rate register.

Parameters
[in]baudrateThe register's Baud Rate field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeStartupFilterBiasEstimate ( StartupFilterBiasEstimateRegister fields,
bool  waitForReply = true 
)

Writes to the Startup Filter Bias Estimate register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeStartupFilterBiasEstimate ( const vn::math::vec3f gyroBias,
const vn::math::vec3f accelBias,
const float &  pressureBias,
bool  waitForReply = true 
)

Writes to the Startup Filter Bias Estimate register.

Parameters
[in]gyroBiasValue for the GyroBias field.
[in]accelBiasValue for the AccelBias field.
[in]pressureBiasValue for the PressureBias field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSynchronizationControl ( SynchronizationControlRegister fields,
bool  waitForReply = true 
)

Writes to the Synchronization Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSynchronizationControl ( protocol::uart::SyncInMode  syncInMode,
protocol::uart::SyncInEdge  syncInEdge,
const uint16_t &  syncInSkipFactor,
protocol::uart::SyncOutMode  syncOutMode,
protocol::uart::SyncOutPolarity  syncOutPolarity,
const uint16_t &  syncOutSkipFactor,
const uint32_t &  syncOutPulseWidth,
bool  waitForReply = true 
)

Writes to the Synchronization Control register.

Parameters
[in]syncInModeValue for the SyncInMode field.
[in]syncInEdgeValue for the SyncInEdge field.
[in]syncInSkipFactorValue for the SyncInSkipFactor field.
[in]syncOutModeValue for the SyncOutMode field.
[in]syncOutPolarityValue for the SyncOutPolarity field.
[in]syncOutSkipFactorValue for the SyncOutSkipFactor field.
[in]syncOutPulseWidthValue for the SyncOutPulseWidth field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSynchronizationStatus ( SynchronizationStatusRegister fields,
bool  waitForReply = true 
)

Writes to the Synchronization Status register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeSynchronizationStatus ( const uint32_t &  syncInCount,
const uint32_t &  syncInTime,
const uint32_t &  syncOutCount,
bool  waitForReply = true 
)

Writes to the Synchronization Status register.

Parameters
[in]syncInCountValue for the SyncInCount field.
[in]syncInTimeValue for the SyncInTime field.
[in]syncOutCountValue for the SyncOutCount field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeUserTag ( const std::string &  tag,
bool  waitForReply = true 
)

Writes to the User Tag register.

Parameters
[in]tagThe register's Tag field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVelocityCompensationControl ( VelocityCompensationControlRegister fields,
bool  waitForReply = true 
)

Writes to the Velocity Compensation Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVelocityCompensationControl ( protocol::uart::VelocityCompensationMode  mode,
const float &  velocityTuning,
const float &  rateTuning,
bool  waitForReply = true 
)

Writes to the Velocity Compensation Control register.

Parameters
[in]modeValue for the Mode field.
[in]velocityTuningValue for the VelocityTuning field.
[in]rateTuningValue for the RateTuning field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVelocityCompensationMeasurement ( const vn::math::vec3f velocity,
bool  waitForReply = true 
)

Writes to the Velocity Compensation Measurement register.

Parameters
[in]velocityThe register's Velocity field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeAccelerometerAdvancedTuning ( VpeAccelerometerAdvancedTuningRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Accelerometer Advanced Tuning register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeAccelerometerAdvancedTuning ( const vn::math::vec3f minFiltering,
const vn::math::vec3f maxFiltering,
const float &  maxAdaptRate,
const float &  disturbanceWindow,
const float &  maxTuning,
bool  waitForReply = true 
)

Writes to the VPE Accelerometer Advanced Tuning register.

Parameters
[in]minFilteringValue for the MinFiltering field.
[in]maxFilteringValue for the MaxFiltering field.
[in]maxAdaptRateValue for the MaxAdaptRate field.
[in]disturbanceWindowValue for the DisturbanceWindow field.
[in]maxTuningValue for the MaxTuning field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeAccelerometerBasicTuning ( VpeAccelerometerBasicTuningRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Accelerometer Basic Tuning register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeAccelerometerBasicTuning ( const vn::math::vec3f baseTuning,
const vn::math::vec3f adaptiveTuning,
const vn::math::vec3f adaptiveFiltering,
bool  waitForReply = true 
)

Writes to the VPE Accelerometer Basic Tuning register.

Parameters
[in]baseTuningValue for the BaseTuning field.
[in]adaptiveTuningValue for the AdaptiveTuning field.
[in]adaptiveFilteringValue for the AdaptiveFiltering field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeBasicControl ( VpeBasicControlRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Basic Control register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
Examples:
getting_started/main.cpp.
void vn::sensors::VnSensor::writeVpeBasicControl ( protocol::uart::VpeEnable  enable,
protocol::uart::HeadingMode  headingMode,
protocol::uart::VpeMode  filteringMode,
protocol::uart::VpeMode  tuningMode,
bool  waitForReply = true 
)

Writes to the VPE Basic Control register.

Parameters
[in]enableValue for the Enable field.
[in]headingModeValue for the HeadingMode field.
[in]filteringModeValue for the FilteringMode field.
[in]tuningModeValue for the TuningMode field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeGyroBasicTuning ( VpeGyroBasicTuningRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Gyro Basic Tuning register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeGyroBasicTuning ( const vn::math::vec3f angularWalkVariance,
const vn::math::vec3f baseTuning,
const vn::math::vec3f adaptiveTuning,
bool  waitForReply = true 
)

Writes to the VPE Gyro Basic Tuning register.

Parameters
[in]angularWalkVarianceValue for the AngularWalkVariance field.
[in]baseTuningValue for the BaseTuning field.
[in]adaptiveTuningValue for the AdaptiveTuning field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeMagnetometerAdvancedTuning ( VpeMagnetometerAdvancedTuningRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Magnetometer Advanced Tuning register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeMagnetometerAdvancedTuning ( const vn::math::vec3f minFiltering,
const vn::math::vec3f maxFiltering,
const float &  maxAdaptRate,
const float &  disturbanceWindow,
const float &  maxTuning,
bool  waitForReply = true 
)

Writes to the VPE Magnetometer Advanced Tuning register.

Parameters
[in]minFilteringValue for the MinFiltering field.
[in]maxFilteringValue for the MaxFiltering field.
[in]maxAdaptRateValue for the MaxAdaptRate field.
[in]disturbanceWindowValue for the DisturbanceWindow field.
[in]maxTuningValue for the MaxTuning field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeMagnetometerBasicTuning ( VpeMagnetometerBasicTuningRegister fields,
bool  waitForReply = true 
)

Writes to the VPE Magnetometer Basic Tuning register.

Parameters
[in]fieldsThe register's fields.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.
void vn::sensors::VnSensor::writeVpeMagnetometerBasicTuning ( const vn::math::vec3f baseTuning,
const vn::math::vec3f adaptiveTuning,
const vn::math::vec3f adaptiveFiltering,
bool  waitForReply = true 
)

Writes to the VPE Magnetometer Basic Tuning register.

Parameters
[in]baseTuningValue for the BaseTuning field.
[in]adaptiveTuningValue for the AdaptiveTuning field.
[in]adaptiveFilteringValue for the AdaptiveFiltering field.
[in]waitForReplyIndicates if the method should wait for a response from the sensor.