16 #include "vn/protocol/upack.h"
17 #include "vn/protocol/upackf.h"
18 #include "vn/xplat/serialport.h"
27 #pragma warning(disable : 4820)
71 CommonGroup commonField,
75 AttitudeGroup attitudeField,
891 typedef void (*VnSensor_PacketFoundHandler)(
void *userData,
VnUartPacket *packet,
size_t runningIndex);
899 VnErrorDetectionMode sendErrorDetectionMode;
902 uint16_t responseTimeoutMs;
905 uint16_t retransmitDelayMs;
912 bool waitingForResponse;
915 bool responseWaitingForProcessing;
917 size_t runningDataIndex;
921 VnSensor_PacketFoundHandler asyncPacketFoundHandler;
922 void *asyncPacketFoundHandlerUserData;
924 VnSensor_PacketFoundHandler errorMessageReceivedHandler;
925 void *errorMessageReceivedHandlerUserData;
927 size_t responseLength;
930 char response[0x100];
1953 #pragma warning(pop)
VnError VnSensor_writeReferenceFrameRotation(VnSensor *sensor, mat3f c, bool waitForReply)
Writes to the Reference Frame Rotation register.
Structure representing the GPS Configuration register.
Definition: sensors.h:455
uint8_t integrationFrame
The IntegrationFrame field.
Definition: sensors.h:740
VnError VnSensor_readInsSolutionLla(VnSensor *sensor, InsSolutionLlaRegister *fields)
Reads the INS Solution - LLA register.
vec3f velocity
The Velocity field.
Definition: sensors.h:698
vec3f velocity
The Velocity field.
Definition: sensors.h:516
float accelerationDisturbanceMemory
The Acceleration Disturbance Memory field.
Definition: sensors.h:161
float filterTargetRate
The filterTargetRate field.
Definition: sensors.h:854
Structure representing the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register...
Definition: sensors.h:862
uint8_t accelFilterMode
The AccelFilterMode field.
Definition: sensors.h:803
vec3f magRef
The MagRef field.
Definition: sensors.h:113
Structure representing the INS Solution - LLA register.
Definition: sensors.h:530
float accelerationDisturbanceGain
The Acceleration Disturbance Gain field.
Definition: sensors.h:155
Structure representing the Filter Basic Control register.
Definition: sensors.h:260
VnError VnSensor_writeDeltaThetaAndDeltaVelocityConfiguration(VnSensor *sensor, DeltaThetaAndDeltaVelocityConfigurationRegister fields, bool waitForReply)
Writes to the Delta Theta and Delta Velocity Configuration register.
float attUncertainty
The AttUncertainty field.
Definition: sensors.h:551
VnError VnSensor_writeAsyncDataOutputType(VnSensor *sensor, VnAsciiAsync ador, bool waitForReply)
Writes to the Async Data Output Type register.
Structure representing the IMU Rate Configuration register.
Definition: sensors.h:845
Data structure holding current parsing status of data received from a VectorNav sensor.
Definition: upackf.h:38
mat3f c
The C field.
Definition: sensors.h:169
vec3f b
The B field.
Definition: sensors.h:777
Structure representing the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates register...
Definition: sensors.h:876
VnError VnSensor_readReferenceVectorConfiguration(VnSensor *sensor, ReferenceVectorConfigurationRegister *fields)
Reads the Reference Vector Configuration register.
vec3f angularRate
The AngularRate field.
Definition: sensors.h:684
uint8_t spiStatus
The SPIStatus field.
Definition: sensors.h:206
uint8_t syncOutMode
The SyncOutMode field.
Definition: sensors.h:232
VnError VnSensor_readMagneticMeasurements(VnSensor *sensor, vec3f *mag)
Reads the Magnetic Measurements register.
uint8_t serialCount
The SerialCount field.
Definition: sensors.h:197
Structure representing the INS Solution - ECEF register.
Definition: sensors.h:562
vec3d position
The Position field.
Definition: sensors.h:695
VnError VnSensor_registerErrorPacketReceivedHandler(VnSensor *sensor, VnSensor_PacketFoundHandler handler, void *userData)
Allows registering a callback for notification of when a sensor error message is received.
VnError VnSensor_readSerialBaudRate(VnSensor *sensor, uint32_t *baudrate)
Reads the Serial Baud Rate register.
float velUncertainty
The VelUncertainty field.
Definition: sensors.h:589
void strFromPpsSource(char *out, VnPpsSource val)
Converts a PpsSource into a string.
Structure representing the Filter Active Tuning Parameters register.
Definition: sensors.h:149
uint8_t gpsFix
The GpsFix field.
Definition: sensors.h:507
VnError VnSensor_writeMagnetometerCompensation(VnSensor *sensor, MagnetometerCompensationRegister fields, bool waitForReply)
Writes to the Magnetometer Compensation register.
VnError VnSensor_setResponseTimeoutMs(VnSensor *sensor, uint16_t reponseTimeoutMs)
Sets the current response timeout value in milliseconds used for communication with a sensor...
VnError VnSensor_writeBinaryOutput1(VnSensor *sensor, BinaryOutputRegister *fields, bool waitForReply)
Writes to the Binary Output 1 register.
VnError VnSensor_readMagneticAndGravityReferenceVectors(VnSensor *sensor, MagneticAndGravityReferenceVectorsRegister *fields)
Reads the Magnetic and Gravity Reference Vectors register.
float rateTuning
The RateTuning field.
Definition: sensors.h:413
VnError VnSensor_writeVpeMagnetometerBasicTuning(VnSensor *sensor, VpeMagnetometerBasicTuningRegister fields, bool waitForReply)
Writes to the VPE Magnetometer Basic Tuning register.
vec3f gyro
The Gyro field.
Definition: sensors.h:885
uint8_t mode
The Mode field.
Definition: sensors.h:458
float angularWalkVariance
The Angular Walk Variance field.
Definition: sensors.h:124
Structure representing the VPE Basic Control register.
Definition: sensors.h:280
VnError VnSensor_writeVpeBasicControl(VnSensor *sensor, VpeBasicControlRegister fields, bool waitForReply)
Writes to the VPE Basic Control register.
void strFromVpeMode(char *out, VnVpeMode val)
Converts a VpeMode into a string.
void strFromCountMode(char *out, VnCountMode val)
Converts a CountMode into a string.
VnError VnSensor_readAccelerationCompensation(VnSensor *sensor, AccelerationCompensationRegister *fields)
Reads the Acceleration Compensation register.
VnError VnSensor_writeReferenceVectorConfiguration(VnSensor *sensor, ReferenceVectorConfigurationRegister fields, bool waitForReply)
Writes to the Reference Vector Configuration register.
AttitudeGroup attitudeField
Definition: sensors.h:51
vec3f uncertainty
The Uncertainty field.
Definition: sensors.h:840
vec3f adaptiveTuning
The AdaptiveTuning field.
Definition: sensors.h:374
Structure representing a UART packet received from a VectorNav sensor.
Definition: upack.h:34
float minVelUncertainty
The MinVelUncertainty field.
Definition: sensors.h:664
void strFromVpeEnable(char *out, VnVpeEnable val)
Converts a VpeEnable into a string.
vec3f omega
The omega field.
Definition: sensors.h:430
void strFromScenario(char *out, VnScenario val)
Converts a Scenario into a string.
uint16_t week
The Week field.
Definition: sensors.h:504
GpsGroup gpsField
Definition: sensors.h:50
VnError VnSensor_readGpsAntennaOffset(VnSensor *sensor, vec3f *position)
Reads the GPS Antenna Offset register.
float moveOrigin
The MoveOrigin field.
Definition: sensors.h:649
vec3f adaptiveFiltering
The AdaptiveFiltering field.
Definition: sensors.h:340
VnError VnSensor_readBinaryOutput3(VnSensor *sensor, BinaryOutputRegister *fields)
Reads the Binary Output 3 register.
VnError VnSensor_readVelocityCompensationMeasurement(VnSensor *sensor, vec3f *velocity)
Reads the Velocity Compensation Measurement register.
void strFromHeadingMode(char *out, VnHeadingMode val)
Converts a HeadingMode into a string.
bool VnSensor_isConnected(VnSensor *sensor)
Indicates if the VnSensor is connected.
float timeAcc
The TimeAcc field.
Definition: sensors.h:525
Structure representing the Startup Filter Bias Estimate register.
Definition: sensors.h:709
CommonGroup commonField
Definition: sensors.h:47
VnError VnSensor_readInsStateEcef(VnSensor *sensor, InsStateEcefRegister *fields)
Reads the INS State - ECEF register.
vec3f accRef
The AccRef field.
Definition: sensors.h:116
uint8_t gpsFix
The GpsFix field.
Definition: sensors.h:475
float attUncertainty
The AttUncertainty field.
Definition: sensors.h:583
uint8_t ahrsAiding
The AhrsAiding field.
Definition: sensors.h:600
VnError VnSensor_reset(VnSensor *sensor, bool waitForReply)
Issues a Reset command to the VectorNav sensor.
uint8_t estBaselineUsed
The EstBaselineUsed field.
Definition: sensors.h:831
vec3f gyro
The Gyro field.
Definition: sensors.h:871
VnError VnSensor_restoreFactorySettings(VnSensor *sensor, bool waitForReply)
Issues a Restore Factory Settings command to the VectorNav sensor.
uint8_t hsiOutput
The HSIOutput field.
Definition: sensors.h:385
Structure representing the VPE Gyro Basic Tuning register.
Definition: sensors.h:365
vec3f angularRate
The AngularRate field.
Definition: sensors.h:704
uint8_t tuningMode
The TuningMode field.
Definition: sensors.h:292
void strFromFoamInit(char *out, VnFoamInit val)
Converts a FoamInit into a string.
float timeAcc
The TimeAcc field.
Definition: sensors.h:493
void strFromGpsMode(char *out, VnGpsMode val)
Converts a GpsMode into a string.
VnError VnSensor_writeVelocityCompensationControl(VnSensor *sensor, VelocityCompensationControlRegister fields, bool waitForReply)
Writes to the Velocity Compensation Control register.
uint16_t gyroWindowSize
The GyroWindowSize field.
Definition: sensors.h:791
VnError VnSensor_readVpeMagnetometerBasicTuning(VnSensor *sensor, VpeMagnetometerBasicTuningRegister *fields)
Reads the VPE Magnetometer Basic Tuning register.
vec3f b
The B field.
Definition: sensors.h:144
vec3f adaptiveTuning
The AdaptiveTuning field.
Definition: sensors.h:303
Helpful structure for working with VectorNav sensors.
Definition: sensors.h:894
void BinaryOutputRegister_initialize(BinaryOutputRegister *reg, AsyncMode asyncMode, uint32_t rateDivisor, CommonGroup commonField, TimeGroup timeField, ImuGroup imuField, GpsGroup gpsField, AttitudeGroup attitudeField, InsGroup insField)
Initializes a BinaryOutputRegister structure.
uint32_t syncInCount
The SyncInCount field.
Definition: sensors.h:249
Structure representing the INS Basic Configuration register for a VN-200 sensor.
Definition: sensors.h:594
Structure representing the INS Basic Configuration register for a VN-300 sensor.
Definition: sensors.h:605
uint16_t presWindowSize
The PresWindowSize field.
Definition: sensors.h:797
vec3f accel
The Accel field.
Definition: sensors.h:102
float maxTuning
The MaxTuning field.
Definition: sensors.h:326
VnError VnSensor_readMagneticAccelerationAndAngularRates(VnSensor *sensor, MagneticAccelerationAndAngularRatesRegister *fields)
Reads the Magnetic, Acceleration and Angular Rates register.
float posUncertainty
The PosUncertainty field.
Definition: sensors.h:586
VnError VnSensor_readInsBasicConfigurationVn200(VnSensor *sensor, InsBasicConfigurationRegisterVn200 *fields)
Reads the INS Basic Configuration register for a VN-200 sensor.
uint8_t headingMode
The HeadingMode field.
Definition: sensors.h:286
vec3f angularRateVariance
The Angular Rate Variance field.
Definition: sensors.h:127
vec3f posAcc
The PosAcc field.
Definition: sensors.h:519
uint16_t tempWindowSize
The TempWindowSize field.
Definition: sensors.h:794
VnError VnSensor_writeVelocityCompensationMeasurement(VnSensor *sensor, vec3f velocity, bool waitForReply)
Writes to the Velocity Compensation Measurement register.
double time
The Time field.
Definition: sensors.h:565
VnError VnSensor_setGyroBias(VnSensor *sensor, bool waitForReply)
Issues a command to the VectorNav Sensor to set the Gyro's bias.
uint8_t estBaseline
The EstBaseline field.
Definition: sensors.h:614
VnError VnSensor_readAsyncDataOutputType(VnSensor *sensor, VnAsciiAsync *ador)
Reads the Async Data Output Type register.
uint8_t useMag
The UseMag field.
Definition: sensors.h:622
vec3f angularWalkVariance
The AngularWalkVariance field.
Definition: sensors.h:368
VnError VnSensor_readGpsConfiguration(VnSensor *sensor, GpsConfigurationRegister *fields)
Reads the GPS Configuration register.
VnError VnSensor_readYawPitchRollMagneticAccelerationAndAngularRates(VnSensor *sensor, YawPitchRollMagneticAccelerationAndAngularRatesRegister *fields)
Reads the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register.
VnError VnSensor_readCalculatedMagnetometerCalibration(VnSensor *sensor, CalculatedMagnetometerCalibrationRegister *fields)
Reads the Calculated Magnetometer Calibration register.
vec3f adaptiveFiltering
The AdaptiveFiltering field.
Definition: sensors.h:306
VnError VnSensor_writeGpsCompassBaseline(VnSensor *sensor, GpsCompassBaselineRegister fields, bool waitForReply)
Writes to the GPS Compass Baseline register.
float gpsTimeout
The GPSTimeout field.
Definition: sensors.h:652
void strFromVelocityCompensationMode(char *out, VnVelocityCompensationMode val)
Converts a VelocityCompensationMode into a string.
vec3d lla
The Lla field.
Definition: sensors.h:481
uint8_t velBias
The VelBias field.
Definition: sensors.h:634
vec3f gyro
The Gyro field.
Definition: sensors.h:91
void strFromSyncInMode(char *out, VnSyncInMode val)
Converts a SyncInMode into a string.
void strFromSyncInEdge(char *out, VnSyncInEdge val)
Converts a SyncInEdge into a string.
VnError VnSensor_writeMagnetometerCalibrationControl(VnSensor *sensor, MagnetometerCalibrationControlRegister fields, bool waitForReply)
Writes to the Magnetometer Calibration Control register.
Structure representing the GPS Compass Baseline register.
Definition: sensors.h:817
void strFromErrorMode(char *out, VnErrorMode val)
Converts a ErrorMode into a string.
VnError VnSensor_readAccelerationMeasurements(VnSensor *sensor, vec3f *accel)
Reads the Acceleration Measurements register.
uint8_t gyroCompensation
The GyroCompensation field.
Definition: sensors.h:743
VnError VnSensor_readGpsCompassEstimatedBaseline(VnSensor *sensor, GpsCompassEstimatedBaselineRegister *fields)
Reads the GPS Compass Estimated Baseline register.
vec3f b
The B field.
Definition: sensors.h:399
Structure representing the Magnetometer Compensation register.
Definition: sensors.h:138
uint16_t syncOutSkipFactor
The SyncOutSkipFactor field.
Definition: sensors.h:238
VnError VnSensor_connect(VnSensor *sensor, const char *portName, uint32_t baudrate)
Connects to a VectorNav sensor.
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:865
VnError VnSensor_writeMagneticAndGravityReferenceVectors(VnSensor *sensor, MagneticAndGravityReferenceVectorsRegister fields, bool waitForReply)
Writes to the Magnetic and Gravity Reference Vectors register.
VnError VnSensor_writeInsBasicConfigurationVn200(VnSensor *sensor, InsBasicConfigurationRegisterVn200 fields, bool waitForReply)
Writes to the INS Basic Configuration register for a VN-200 sensor.
uint16_t week
The Week field.
Definition: sensors.h:472
VnError VnSensor_writeSynchronizationControl(VnSensor *sensor, SynchronizationControlRegister fields, bool waitForReply)
Writes to the Synchronization Control register.
void strFromHsiMode(char *out, VnHsiMode val)
Converts a HsiMode into a string.
vec3f mag
The Mag field.
Definition: sensors.h:85
uint8_t accelCompensation
The AccelCompensation field.
Definition: sensors.h:746
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:879
Structure representing the INS State - ECEF register.
Definition: sensors.h:689
void strFromGpsFix(char *out, VnGpsFix val)
Converts a GpsFix into a string.
uint8_t gyroFilterMode
The GyroFilterMode field.
Definition: sensors.h:806
uint8_t ahrsAiding
The AhrsAiding field.
Definition: sensors.h:611
Provides access to a serial port.
Definition: serialport.h:48
vec3f position
The Position field.
Definition: sensors.h:837
vec4f quat
The Quat field.
Definition: sensors.h:82
Structure representing the IMU Filtering Configuration register.
Definition: sensors.h:782
uint16_t numMeas
The NumMeas field.
Definition: sensors.h:834
VnError VnSensor_initialize(VnSensor *sensor)
Initializes a VnSensor structure.
uint16_t week
The Week field.
Definition: sensors.h:536
VnError VnSensor_readAngularRateMeasurements(VnSensor *sensor, vec3f *gyro)
Reads the Angular Rate Measurements register.
VnError VnSensor_readStartupFilterBiasEstimate(VnSensor *sensor, StartupFilterBiasEstimateRegister *fields)
Reads the Startup Filter Bias Estimate register.
uint32_t recalcThreshold
The RecalcThreshold field.
Definition: sensors.h:760
VnError VnSensor_readDeltaThetaAndDeltaVelocity(VnSensor *sensor, DeltaThetaAndDeltaVelocityRegister *fields)
Reads the Delta Theta and Delta Velocity register.
uint8_t usePres
The UsePres field.
Definition: sensors.h:625
VnError VnSensor_readVelocityCompensationControl(VnSensor *sensor, VelocityCompensationControlRegister *fields)
Reads the Velocity Compensation Control register.
VnError VnSensor_readReferenceFrameRotation(VnSensor *sensor, mat3f *c)
Reads the Reference Frame Rotation register.
Structure representing the Gyro Compensation register.
Definition: sensors.h:771
vec3f gyroBias
The GyroBias field.
Definition: sensors.h:712
VnError VnSensor_readBinaryOutput2(VnSensor *sensor, BinaryOutputRegister *fields)
Reads the Binary Output 2 register.
double tow
The Tow field.
Definition: sensors.h:501
vec3f accel
The Accel field.
Definition: sensors.h:441
VnError VnSensor_readImuMeasurements(VnSensor *sensor, ImuMeasurementsRegister *fields)
Reads the IMU Measurements register.
vec3f deltaTheta
The DeltaTheta field.
Definition: sensors.h:729
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:672
vec3f mag
The Mag field.
Definition: sensors.h:183
VnError VnSensor_readInsBasicConfigurationVn300(VnSensor *sensor, InsBasicConfigurationRegisterVn300 *fields)
Reads the INS Basic Configuration register for a VN-300 sensor.
uint16_t VnSensor_getResponseTimeoutMs(VnSensor *sensor)
Returns the current response timeout value in milliseconds used for communication with a sensor...
vec3f uncertainty
The Uncertainty field.
Definition: sensors.h:823
VnError VnSensor_readGpsCompassBaseline(VnSensor *sensor, GpsCompassBaselineRegister *fields)
Reads the GPS Compass Baseline register.
uint32_t syncOutCount
The SyncOutCount field.
Definition: sensors.h:255
Represents a 4 component vector with an underlying data type of float.
Definition: vector.h:68
VnError VnSensor_writeSerialBaudRate(VnSensor *sensor, uint32_t baudrate, bool waitForReply)
Writes to the Serial Baud Rate register.
Structure representing the Quaternion, Magnetic, Acceleration and Angular Rates register.
Definition: sensors.h:79
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:542
float posUncertainty
The PosUncertainty field.
Definition: sensors.h:554
float minPosUncertainty
The MinPosUncertainty field.
Definition: sensors.h:661
uint8_t magMode
The MagMode field.
Definition: sensors.h:263
VnError VnSensor_readMagnetometerCompensation(VnSensor *sensor, MagnetometerCompensationRegister *fields)
Reads the Magnetometer Compensation register.
VnError VnSensor_writeAsyncDataOutputFrequency(VnSensor *sensor, uint32_t adof, bool waitForReply)
Writes to the Async Data Output Frequency register.
vec3f adaptiveTuning
The AdaptiveTuning field.
Definition: sensors.h:337
void strFromFilterMode(char *out, VnFilterMode val)
Converts a FilterMode into a string.
Structure representing an event.
Definition: event.h:41
Represents a 3 component vector with an underlying data type of double.
Definition: vector.h:41
float velInit
The VelInit field.
Definition: sensors.h:646
VnError VnSensor_writeGyroCompensation(VnSensor *sensor, GyroCompensationRegister fields, bool waitForReply)
Writes to the Gyro Compensation register.
float deltaTime
The DeltaTime field.
Definition: sensors.h:726
bool VnSensor_verifySensorConnectivity(VnSensor *sensor)
Checks if we are able to send and receive communication with a sensor.
uint16_t imuRate
The imuRate field.
Definition: sensors.h:848
InsGroup insField
Definition: sensors.h:52
Structure representing the GPS Solution - ECEF register.
Definition: sensors.h:498
uint16_t navDivisor
The NavDivisor field.
Definition: sensors.h:851
uint8_t gpsCovType
The GPSCovType field.
Definition: sensors.h:640
VnError VnSensor_accelerationDisturbancePresent(VnSensor *sensor, bool disturbancePresent, bool waitForReply)
Command to inform the VectorNav Sensor if there is an acceleration disturbance present.
VnError VnSensor_registerAsyncPacketReceivedHandler(VnSensor *sensor, VnSensor_PacketFoundHandler handler, void *userData)
Allows registering a callback for notification of when an asynchronous data packet is received...
uint8_t numSats
The NumSats field.
Definition: sensors.h:510
VnError VnSensor_writeBinaryOutput3(VnSensor *sensor, BinaryOutputRegister *fields, bool waitForReply)
Writes to the Binary Output 3 register.
void strFromChecksumMode(char *out, VnChecksumMode val)
Converts a ChecksumMode into a string.
Structure representing the Synchronization Status register.
Definition: sensors.h:246
vec3d position
The Position field.
Definition: sensors.h:577
vec3f accelBias
The AccelBias field.
Definition: sensors.h:715
vec3f velocity
The Velocity field.
Definition: sensors.h:678
VnError VnSensor_unregisterErrorPacketReceivedHandler(VnSensor *sensor)
Allows unregistering callbacks for notifications of when a sensor error message is recieved...
vec3f b
The B field.
Definition: sensors.h:172
Structure representing the Delta Theta and Delta Velocity register.
Definition: sensors.h:723
Structure representing the VPE Magnetometer Basic Tuning register.
Definition: sensors.h:297
vec3f gyroLimit
The GyroLimit field.
Definition: sensors.h:275
uint8_t useMagModel
The UseMagModel field.
Definition: sensors.h:754
VnError VnSensor_readFirmwareVersion(VnSensor *sensor, char *firmwareVersionBuffer, size_t firmwareVersionBufferLength)
Reads the Firmware Version register.
void strFromCompensationMode(char *out, VnCompensationMode val)
Converts a CompensationMode into a string.
VnError VnSensor_unregisterAsyncPacketReceivedHandler(VnSensor *sensor)
Allows unregistering from callback notifications when asynchronous data packets are received...
vec3f deltaVelocity
The DeltaVelocity field.
Definition: sensors.h:732
VnError VnSensor_readVpeAccelerometerBasicTuning(VnSensor *sensor, VpeAccelerometerBasicTuningRegister *fields)
Reads the VPE Accelerometer Basic Tuning register.
Structure representing the Delta Theta and Delta Velocity Configuration register. ...
Definition: sensors.h:737
float speedAcc
The SpeedAcc field.
Definition: sensors.h:490
Structure representing the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register...
Definition: sensors.h:177
uint8_t posAtt
The PosAtt field.
Definition: sensors.h:628
vec3f nedVel
The NedVel field.
Definition: sensors.h:484
VnError VnSensor_magneticDisturbancePresent(VnSensor *sensor, bool disturbancePresent, bool waitForReply)
Command to inform the VectorNav Sensor if there is a magnetic disturbance present.
vec3f bodyAccel
The BodyAccel field.
Definition: sensors.h:868
uint8_t velCount
The VelCount field.
Definition: sensors.h:643
vec3d position
The Position field.
Definition: sensors.h:545
vec3f inertialAccel
The InertialAccel field.
Definition: sensors.h:882
vec3f baseTuning
The BaseTuning field.
Definition: sensors.h:371
uint8_t spiCount
The SPICount field.
Definition: sensors.h:203
void strFromSyncOutMode(char *out, VnSyncOutMode val)
Converts a SyncOutMode into a string.
AsyncMode asyncMode
Definition: sensors.h:45
uint8_t velAtt
The VelAtt field.
Definition: sensors.h:631
uint8_t hsiMode
The HSIMode field.
Definition: sensors.h:382
VnError VnSensor_readCommunicationProtocolControl(VnSensor *sensor, CommunicationProtocolControlRegister *fields)
Reads the Communication Protocol Control register.
VnError VnSensor_readMagnetometerCalibrationControl(VnSensor *sensor, MagnetometerCalibrationControlRegister *fields)
Reads the Magnetometer Calibration Control register.
Structure representing the Velocity Compensation Control register.
Definition: sensors.h:404
vec3f mag
The Mag field.
Definition: sensors.h:99
Structure representing the IMU Measurements register.
Definition: sensors.h:435
VnError VnSensor_writeCommunicationProtocolControl(VnSensor *sensor, CommunicationProtocolControlRegister fields, bool waitForReply)
Writes to the Communication Protocol Control register.
VnError VnSensor_readBinaryOutput1(VnSensor *sensor, BinaryOutputRegister *fields)
Reads the Binary Output 1 register.
uint16_t magWindowSize
The MagWindowSize field.
Definition: sensors.h:785
uint16_t week
The Week field.
Definition: sensors.h:568
uint16_t status
The Status field.
Definition: sensors.h:571
float disturbanceWindow
The DisturbanceWindow field.
Definition: sensors.h:323
Structure representing the GPS Compass Estimated Baseline register.
Definition: sensors.h:828
uint16_t VnSensor_getRetransmitDelayMs(VnSensor *sensor)
Gets the current retransmit delay used for communication with a sensor.
void strFromSyncOutPolarity(char *out, VnSyncOutPolarity val)
Converts a SyncOutPolarity into a string.
double time
The Time field.
Definition: sensors.h:533
VnError VnSensor_disconnect(VnSensor *sensor)
Disconnects from a VectorNav sensor.
float x
The x field.
Definition: sensors.h:421
Definition: criticalsection.h:38
uint32_t syncOutPulseWidth
The SyncOutPulseWidth field.
Definition: sensors.h:241
VnError VnSensor_readGyroCompensation(VnSensor *sensor, GyroCompensationRegister *fields)
Reads the Gyro Compensation register.
uint16_t status
The Status field.
Definition: sensors.h:539
vec3f minFiltering
The MinFiltering field.
Definition: sensors.h:314
vec3f accel
The Accel field.
Definition: sensors.h:186
vec3f nedVel
The NedVel field.
Definition: sensors.h:548
vec3f magneticVariance
The Magnetic Variance field.
Definition: sensors.h:130
VnError VnSensor_writeVpeAccelerometerBasicTuning(VnSensor *sensor, VpeAccelerometerBasicTuningRegister fields, bool waitForReply)
Writes to the VPE Accelerometer Basic Tuning register.
uint8_t errorMode
The ErrorMode field.
Definition: sensors.h:215
void strFromHsiOutput(char *out, VnHsiOutput val)
Converts a HsiOutput into a string.
uint8_t enable
The Enable field.
Definition: sensors.h:283
VnError VnSensor_readQuaternionMagneticAccelerationAndAngularRates(VnSensor *sensor, QuaternionMagneticAccelerationAndAngularRatesRegister *fields)
Reads the Quaternion, Magnetic, Acceleration and Angular Rates register.
VnError VnSensor_readYawPitchRoll(VnSensor *sensor, vec3f *yawPitchRoll)
Reads the Yaw Pitch Roll register.
vec3f position
The Position field.
Definition: sensors.h:820
uint8_t scenario
The Scenario field.
Definition: sensors.h:597
double time
The Time field.
Definition: sensors.h:469
Structure representing the Calculated Magnetometer Calibration register.
Definition: sensors.h:393
vec3f accel
The Accel field.
Definition: sensors.h:88
float pressureBias
The PressureBias field.
Definition: sensors.h:718
float maxTuning
The MaxTuning field.
Definition: sensors.h:360
vec3f baseTuning
The BaseTuning field.
Definition: sensors.h:334
vec3f gyro
The Gyro field.
Definition: sensors.h:105
uint8_t useGravityModel
The UseGravityModel field.
Definition: sensors.h:757
VnError VnSensor_readSerialNumber(VnSensor *sensor, uint32_t *serialNum)
Reads the Serial Number register.
VnError VnSensor_readHardwareRevision(VnSensor *sensor, uint32_t *revision)
Reads the Hardware Revision register.
uint8_t filteringMode
The FilteringMode field.
Definition: sensors.h:289
uint8_t convergeRate
The ConvergeRate field.
Definition: sensors.h:388
uint8_t syncInEdge
The SyncInEdge field.
Definition: sensors.h:226
Structure representing the Reference Vector Configuration register.
Definition: sensors.h:751
vec3f accel
The Accel field.
Definition: sensors.h:701
vec3f maxFiltering
The MaxFiltering field.
Definition: sensors.h:317
VnError VnSensor_writeGpsAntennaOffset(VnSensor *sensor, vec3f position, bool waitForReply)
Writes to the GPS Antenna Offset register.
VnError VnSensor_writeStartupFilterBiasEstimate(VnSensor *sensor, StartupFilterBiasEstimateRegister fields, bool waitForReply)
Writes to the Startup Filter Bias Estimate register.
vec3f nedAcc
The NedAcc field.
Definition: sensors.h:487
vec3f maxFiltering
The MaxFiltering field.
Definition: sensors.h:351
VnError VnSensor_readModelNumber(VnSensor *sensor, char *productNameBuffer, size_t productNameBufferLength)
Reads the Model Number register.
Structure representing the Magnetometer Calibration Control register.
Definition: sensors.h:379
vec3f accelerationVariance
The Acceleration Variance field.
Definition: sensors.h:133
VnError VnSensor_writeGpsConfiguration(VnSensor *sensor, GpsConfigurationRegister fields, bool waitForReply)
Writes to the GPS Configuration register.
float magneticDisturbanceMemory
The Magnetic Disturbance Memory field.
Definition: sensors.h:158
uint32_t syncInTime
The SyncInTime field.
Definition: sensors.h:252
uint16_t rateDivisor
Definition: sensors.h:46
vec3f minFiltering
The MinFiltering field.
Definition: sensors.h:348
uint8_t serialStatus
The SerialStatus field.
Definition: sensors.h:200
vec3f velocity
The Velocity field.
Definition: sensors.h:580
void strFromExternalSensorMode(char *out, VnExternalSensorMode val)
Converts a ExternalSensorMode into a string.
vec3f accel
The Accel field.
Definition: sensors.h:681
uint8_t useFoam
The UseFoam field.
Definition: sensors.h:637
uint8_t magFilterMode
The MagFilterMode field.
Definition: sensors.h:800
vec3f mag
The Mag field.
Definition: sensors.h:438
uint8_t tempFilterMode
The TempFilterMode field.
Definition: sensors.h:809
VnError VnSensor_writeSynchronizationStatus(VnSensor *sensor, SynchronizationStatusRegister fields, bool waitForReply)
Writes to the Synchronization Status register.
mat3f c
The C field.
Definition: sensors.h:774
vec3f accelOffset
The accelOffset field.
Definition: sensors.h:427
uint16_t accelWindowSize
The AccelWindowSize field.
Definition: sensors.h:788
float deltaLimitPos
The DeltaLimitPos field.
Definition: sensors.h:655
VnError VnSensor_readSynchronizationControl(VnSensor *sensor, SynchronizationControlRegister *fields)
Reads the Synchronization Control register.
VnError VnSensor_readUserTag(VnSensor *sensor, char *tagBuffer, size_t tagBufferLength)
Reads the User Tag register.
Structure representing a Binary Output register.
Definition: sensors.h:43
vec3d position
The Position field.
Definition: sensors.h:513
void strFromStatusMode(char *out, VnStatusMode val)
Converts a StatusMode into a string.
Structure representing the INS State - LLA register.
Definition: sensors.h:669
VnError VnSensor_transaction(VnSensor *sensor, char *toSend, size_t toSendLength, char *response, size_t *responseLength)
Sends the provided command and returns the response from the sensor.
float maxAdaptRate
The MaxAdaptRate field.
Definition: sensors.h:320
VnError VnSensor_writeSettings(VnSensor *sensor, bool waitForReply)
Issues a Write Settings command to the VectorNav Sensor.
Represents a 3x3 matrix with an underlying data type of float.
Definition: matrix.h:11
float pressure
The Pressure field.
Definition: sensors.h:450
Structure representing the Synchronization Control register.
Definition: sensors.h:220
uint8_t serialChecksum
The SerialChecksum field.
Definition: sensors.h:209
Structure representing the Magnetic and Gravity Reference Vectors register.
Definition: sensors.h:110
VnError VnSensor_readImuFilteringConfiguration(VnSensor *sensor, ImuFilteringConfigurationRegister *fields)
Reads the IMU Filtering Configuration register.
VnError VnSensor_readInsStateLla(VnSensor *sensor, InsStateLlaRegister *fields)
Reads the INS State - LLA register.
VnError VnSensor_writeInsBasicConfigurationVn300(VnSensor *sensor, InsBasicConfigurationRegisterVn300 fields, bool waitForReply)
Writes to the INS Basic Configuration register for a VN-300 sensor.
float xDot
The xDot field.
Definition: sensors.h:424
void strFromIntegrationFrame(char *out, VnIntegrationFrame val)
Converts a IntegrationFrame into a string.
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:692
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:574
uint8_t extAccMode
The ExtAccMode field.
Definition: sensors.h:269
mat3f c
The C field.
Definition: sensors.h:141
void strFromMagneticMode(char *out, VnMagneticMode val)
Converts a MagneticMode into a string.
float disturbanceWindow
The DisturbanceWindow field.
Definition: sensors.h:357
VnError VnSensor_readAttitudeQuaternion(VnSensor *sensor, vec4f *quat)
Reads the Attitude Quaternion register.
VnError VnSensor_writeBinaryOutput2(VnSensor *sensor, BinaryOutputRegister *fields, bool waitForReply)
Writes to the Binary Output 2 register.
vec3d position
The Position field.
Definition: sensors.h:675
vec3f yawPitchRoll
The YawPitchRoll field.
Definition: sensors.h:180
Structure representing the VPE Accelerometer Basic Tuning register.
Definition: sensors.h:331
float year
The Year field.
Definition: sensors.h:763
VnError VnSensor_writeAccelerationCompensation(VnSensor *sensor, AccelerationCompensationRegister fields, bool waitForReply)
Writes to the Acceleration Compensation register.
vec3d position
The Position field.
Definition: sensors.h:766
float magneticDisturbanceGain
The Magnetic Disturbance Gain field.
Definition: sensors.h:152
uint16_t syncInSkipFactor
The SyncInSkipFactor field.
Definition: sensors.h:229
float filterMinRate
The filterMinRate field.
Definition: sensors.h:857
vec3f gyro
The Gyro field.
Definition: sensors.h:444
VnError VnSensor_readGpsSolutionEcef(VnSensor *sensor, GpsSolutionEcefRegister *fields)
Reads the GPS Solution - ECEF register.
uint8_t extMagMode
The ExtMagMode field.
Definition: sensors.h:266
uint8_t syncInMode
The SyncInMode field.
Definition: sensors.h:223
vec3f baseTuning
The BaseTuning field.
Definition: sensors.h:300
uint8_t scenario
The Scenario field.
Definition: sensors.h:608
VnError VnSensor_writeUserTag(VnSensor *sensor, char *tag, bool waitForReply)
Writes to the User Tag register.
float maxAdaptRate
The MaxAdaptRate field.
Definition: sensors.h:354
VnError VnSensor_readDeltaThetaAndDeltaVelocityConfiguration(VnSensor *sensor, DeltaThetaAndDeltaVelocityConfigurationRegister *fields)
Reads the Delta Theta and Delta Velocity Configuration register.
uint8_t presFilterMode
The PresFilterMode field.
Definition: sensors.h:812
uint8_t extGyroMode
The ExtGyroMode field.
Definition: sensors.h:272
ImuGroup imuField
Definition: sensors.h:49
Structure representing the VPE Accelerometer Advanced Tuning register.
Definition: sensors.h:345
uint8_t ppsSource
The PpsSource field.
Definition: sensors.h:461
uint8_t syncOutPolarity
The SyncOutPolarity field.
Definition: sensors.h:235
vec3f gyro
The Gyro field.
Definition: sensors.h:189
Various vector types and operations.
Definition: vector.h:14
float velUncertainty
The VelUncertainty field.
Definition: sensors.h:557
Structure representing the Magnetic, Acceleration and Angular Rates register.
Definition: sensors.h:96
VnError VnSensor_writeImuFilteringConfiguration(VnSensor *sensor, ImuFilteringConfigurationRegister fields, bool waitForReply)
Writes to the IMU Filtering Configuration register.
Structure representing the Acceleration Compensation register.
Definition: sensors.h:166
float velocityTuning
The VelocityTuning field.
Definition: sensors.h:410
Structure representing the GPS Solution - LLA register.
Definition: sensors.h:466
float deltaLimitVel
The DeltaLimitVel field.
Definition: sensors.h:658
uint8_t numSats
The NumSats field.
Definition: sensors.h:478
VnError VnSensor_readInsSolutionEcef(VnSensor *sensor, InsSolutionEcefRegister *fields)
Reads the INS Solution - ECEF register.
Structure representing the VPE Magnetometer Advanced Tuning register.
Definition: sensors.h:311
VnError VnSensor_changeBaudrate(VnSensor *sensor, uint32_t baudrate)
Issues a change baudrate to the VectorNav sensor and then reconnectes the attached serial port at the...
Structure representing the INS Advanced Configuration register.
Definition: sensors.h:619
VnError VnSensor_tare(VnSensor *sensor, bool waitForReply)
Issues a tare command to the VectorNav Sensor.
void strFromSensorError(char *out, SensorError val)
Converts a sensor error into a string.
uint8_t mode
The Mode field.
Definition: sensors.h:407
Structure representing the Communication Protocol Control register.
Definition: sensors.h:194
TimeGroup timeField
Definition: sensors.h:48
VnError VnSensor_readAsyncDataOutputFrequency(VnSensor *sensor, uint32_t *adof)
Reads the Async Data Output Frequency register.
VnError VnSensor_readVpeBasicControl(VnSensor *sensor, VpeBasicControlRegister *fields)
Reads the VPE Basic Control register.
VnError VnSensor_readYawPitchRollTrueBodyAccelerationAndAngularRates(VnSensor *sensor, YawPitchRollTrueBodyAccelerationAndAngularRatesRegister *fields)
Reads the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register.
Structure representing the Velocity Compensation Status register.
Definition: sensors.h:418
mat3f c
The C field.
Definition: sensors.h:396
uint8_t spiChecksum
The SPIChecksum field.
Definition: sensors.h:212
VnError VnSensor_setRetransmitDelayMs(VnSensor *sensor, uint16_t retransmitDelayMs)
Sets the current retransmit delay used for communication with a sensor.
VnError VnSensor_readYawPitchRollTrueInertialAccelerationAndAngularRates(VnSensor *sensor, YawPitchRollTrueInertialAccelerationAndAngularRatesRegister *fields)
Reads the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates register.
float speedAcc
The SpeedAcc field.
Definition: sensors.h:522
float temp
The Temp field.
Definition: sensors.h:447
Structure representing the Filter Measurements Variance Parameters register.
Definition: sensors.h:121
VnError VnSensor_readGpsSolutionLla(VnSensor *sensor, GpsSolutionLlaRegister *fields)
Reads the GPS Solution - LLA register.
VnError VnSensor_readSynchronizationStatus(VnSensor *sensor, SynchronizationStatusRegister *fields)
Reads the Synchronization Status register.