2024-06-12 19:47:42 +02:00

876 lines
21 KiB
C++

/** \file
* {COMMON_HEADER}
*
* \section Description
* This header file contains declarations for using VectorNav sensors.
*/
#ifndef _VNSENSORS_H_
#define _VNSENSORS_H_
#include <stddef.h>
#include <stdio.h>
#include "enum.h"
#include "int.h"
#include "math/matrix.h"
#include "math/vector.h"
#ifdef __cplusplus
extern "C" {
namespace vn {
#endif
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable : 4820)
#endif
// Define the max record size of a firmware update file
#define MAXFIRMWAREUPDATERECORDSIZE 300
/** \defgroup registerStructures Register Structures
* \brief These structures represent the various registers on a VecotorNav
* sensor.
*
* \{ */
/** \brief Structure representing a Binary Output register.
*
* The field outputGroup available on the sensor's register is not necessary
* in this structure since all read/writes operations will automatically
* determine this from the settings for the individual groups within this
* structure. */
typedef struct {
AsyncMode asyncMode; /**< The asyncMode field. */
uint16_t rateDivisor; /**< The rateDivisor field. */
CommonGroup commonField; /**< Group 1 (Common) */
TimeGroup timeField; /**< Group 2 (Time) */
ImuGroup imuField; /**< Group 3 (IMU) */
GpsGroup gpsField; /**< Group 4 (GPS) */
AttitudeGroup attitudeField; /**< Group 5 (Attitude) */
InsGroup insField; /**< Group 6 (INS) */
GpsGroup gps2Field; /**< Group 7 (GPS2) */
} BinaryOutputRegister;
/** \brief Initializes a BinaryOutputRegister structure.
*
* \param[in] reg The BinaryOutputRegister structure to initialize.
* \param[in] asyncMode Value to initialize the asyncMode field with.
* \param[in] rateDivisor Value to initialize the rateDivisor field with.
* \param[in] commonField Value to initialize the commonField with.
* \param[in] timeField Value to initialize the timeField with.
* \param[in] imuField Value to initialize the imuField with.
* \param[in] gpsField Value to initialize the gpsField with.
* \param[in] attitudeField Value to initialize the attitudeField with.
* \param[in] insField Value to initialize the insField with. */
void BinaryOutputRegister_initialize(BinaryOutputRegister *reg, AsyncMode asyncMode, uint32_t rateDivisor, CommonGroup commonField,
TimeGroup timeField, ImuGroup imuField, GpsGroup gpsField, AttitudeGroup attitudeField, InsGroup insField,
GpsGroup gps2Field);
/** \brief Structure representing the Quaternion, Magnetic, Acceleration and Angular Rates register. */
typedef struct {
/** \brief The Quat field. */
vec4f quat;
/** \brief The Mag field. */
vec3f mag;
/** \brief The Accel field. */
vec3f accel;
/** \brief The Gyro field. */
vec3f gyro;
} QuaternionMagneticAccelerationAndAngularRatesRegister;
/** \brief Structure representing the Magnetic, Acceleration and Angular Rates register. */
typedef struct {
/** \brief The Mag field. */
vec3f mag;
/** \brief The Accel field. */
vec3f accel;
/** \brief The Gyro field. */
vec3f gyro;
} MagneticAccelerationAndAngularRatesRegister;
/** \brief Structure representing the Magnetic and Gravity Reference Vectors register. */
typedef struct {
/** \brief The MagRef field. */
vec3f magRef;
/** \brief The AccRef field. */
vec3f accRef;
} MagneticAndGravityReferenceVectorsRegister;
/** \brief Structure representing the Filter Measurements Variance Parameters register. */
typedef struct {
/** \brief The Angular Walk Variance field. */
float angularWalkVariance;
/** \brief The Angular Rate Variance field. */
vec3f angularRateVariance;
/** \brief The Magnetic Variance field. */
vec3f magneticVariance;
/** \brief The Acceleration Variance field. */
vec3f accelerationVariance;
} FilterMeasurementsVarianceParametersRegister;
/** \brief Structure representing the Magnetometer Compensation register. */
typedef struct {
/** \brief The C field. */
mat3f c;
/** \brief The B field. */
vec3f b;
} MagnetometerCompensationRegister;
/** \brief Structure representing the Filter Active Tuning Parameters register. */
typedef struct {
/** \brief The Magnetic Disturbance Gain field. */
float magneticDisturbanceGain;
/** \brief The Acceleration Disturbance Gain field. */
float accelerationDisturbanceGain;
/** \brief The Magnetic Disturbance Memory field. */
float magneticDisturbanceMemory;
/** \brief The Acceleration Disturbance Memory field. */
float accelerationDisturbanceMemory;
} FilterActiveTuningParametersRegister;
/** \brief Structure representing the Acceleration Compensation register. */
typedef struct {
/** \brief The C field. */
mat3f c;
/** \brief The B field. */
vec3f b;
} AccelerationCompensationRegister;
/** \brief Structure representing the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register. */
typedef struct {
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The Mag field. */
vec3f mag;
/** \brief The Accel field. */
vec3f accel;
/** \brief The Gyro field. */
vec3f gyro;
} YawPitchRollMagneticAccelerationAndAngularRatesRegister;
/** \brief Structure representing the Communication Protocol Control register. */
typedef struct {
/** \brief The SerialCount field. */
uint8_t serialCount;
/** \brief The SerialStatus field. */
uint8_t serialStatus;
/** \brief The SPICount field. */
uint8_t spiCount;
/** \brief The SPIStatus field. */
uint8_t spiStatus;
/** \brief The SerialChecksum field. */
uint8_t serialChecksum;
/** \brief The SPIChecksum field. */
uint8_t spiChecksum;
/** \brief The ErrorMode field. */
uint8_t errorMode;
} CommunicationProtocolControlRegister;
/** \brief Structure representing the Synchronization Control register. */
typedef struct {
/** \brief The SyncInMode field. */
uint8_t syncInMode;
/** \brief The SyncInEdge field. */
uint8_t syncInEdge;
/** \brief The SyncInSkipFactor field. */
uint16_t syncInSkipFactor;
/** \brief The SyncOutMode field. */
uint8_t syncOutMode;
/** \brief The SyncOutPolarity field. */
uint8_t syncOutPolarity;
/** \brief The SyncOutSkipFactor field. */
uint16_t syncOutSkipFactor;
/** \brief The SyncOutPulseWidth field. */
uint32_t syncOutPulseWidth;
} SynchronizationControlRegister;
/** \brief Structure representing the Synchronization Status register. */
typedef struct {
/** \brief The SyncInCount field. */
uint32_t syncInCount;
/** \brief The SyncInTime field. */
uint32_t syncInTime;
/** \brief The SyncOutCount field. */
uint32_t syncOutCount;
} SynchronizationStatusRegister;
/** \brief Structure representing the Filter Basic Control register. */
typedef struct {
/** \brief The MagMode field. */
uint8_t magMode;
/** \brief The ExtMagMode field. */
uint8_t extMagMode;
/** \brief The ExtAccMode field. */
uint8_t extAccMode;
/** \brief The ExtGyroMode field. */
uint8_t extGyroMode;
/** \brief The GyroLimit field. */
vec3f gyroLimit;
} FilterBasicControlRegister;
/** \brief Structure representing the VPE Basic Control register. */
typedef struct {
/** \brief The Enable field. */
uint8_t enable;
/** \brief The HeadingMode field. */
uint8_t headingMode;
/** \brief The FilteringMode field. */
uint8_t filteringMode;
/** \brief The TuningMode field. */
uint8_t tuningMode;
} VpeBasicControlRegister;
/** \brief Structure representing the VPE Magnetometer Basic Tuning register. */
typedef struct {
/** \brief The BaseTuning field. */
vec3f baseTuning;
/** \brief The AdaptiveTuning field. */
vec3f adaptiveTuning;
/** \brief The AdaptiveFiltering field. */
vec3f adaptiveFiltering;
} VpeMagnetometerBasicTuningRegister;
/** \brief Structure representing the VPE Magnetometer Advanced Tuning register. */
typedef struct {
/** \brief The MinFiltering field. */
vec3f minFiltering;
/** \brief The MaxFiltering field. */
vec3f maxFiltering;
/** \brief The MaxAdaptRate field. */
float maxAdaptRate;
/** \brief The DisturbanceWindow field. */
float disturbanceWindow;
/** \brief The MaxTuning field. */
float maxTuning;
} VpeMagnetometerAdvancedTuningRegister;
/** \brief Structure representing the VPE Accelerometer Basic Tuning register. */
typedef struct {
/** \brief The BaseTuning field. */
vec3f baseTuning;
/** \brief The AdaptiveTuning field. */
vec3f adaptiveTuning;
/** \brief The AdaptiveFiltering field. */
vec3f adaptiveFiltering;
} VpeAccelerometerBasicTuningRegister;
/** \brief Structure representing the VPE Accelerometer Advanced Tuning register. */
typedef struct {
/** \brief The MinFiltering field. */
vec3f minFiltering;
/** \brief The MaxFiltering field. */
vec3f maxFiltering;
/** \brief The MaxAdaptRate field. */
float maxAdaptRate;
/** \brief The DisturbanceWindow field. */
float disturbanceWindow;
/** \brief The MaxTuning field. */
float maxTuning;
} VpeAccelerometerAdvancedTuningRegister;
/** \brief Structure representing the VPE Gyro Basic Tuning register. */
typedef struct {
/** \brief The AngularWalkVariance field. */
vec3f angularWalkVariance;
/** \brief The BaseTuning field. */
vec3f baseTuning;
/** \brief The AdaptiveTuning field. */
vec3f adaptiveTuning;
} VpeGyroBasicTuningRegister;
/** \brief Structure representing the Magnetometer Calibration Control register. */
typedef struct {
/** \brief The HSIMode field. */
uint8_t hsiMode;
/** \brief The HSIOutput field. */
uint8_t hsiOutput;
/** \brief The ConvergeRate field. */
uint8_t convergeRate;
} MagnetometerCalibrationControlRegister;
/** \brief Structure representing the Calculated Magnetometer Calibration register. */
typedef struct {
/** \brief The C field. */
mat3f c;
/** \brief The B field. */
vec3f b;
} CalculatedMagnetometerCalibrationRegister;
/** \brief Structure representing the Velocity Compensation Control register. */
typedef struct {
/** \brief The Mode field. */
uint8_t mode;
/** \brief The VelocityTuning field. */
float velocityTuning;
/** \brief The RateTuning field. */
float rateTuning;
} VelocityCompensationControlRegister;
/** \brief Structure representing the Velocity Compensation Status register. */
typedef struct {
/** \brief The x field. */
float x;
/** \brief The xDot field. */
float xDot;
/** \brief The accelOffset field. */
vec3f accelOffset;
/** \brief The omega field. */
vec3f omega;
} VelocityCompensationStatusRegister;
/** \brief Structure representing the IMU Measurements register. */
typedef struct ImuMeasurementsRegister {
/** \brief The Mag field. */
vec3f mag;
/** \brief The Accel field. */
vec3f accel;
/** \brief The Gyro field. */
vec3f gyro;
/** \brief The Temp field. */
float temp;
/** \brief The Pressure field. */
float pressure;
ImuMeasurementsRegister() {
temp = 0.0;
pressure = 0.0;
};
};
/** \brief Structure representing the GPS Configuration register. */
typedef struct {
/** \brief The Mode field. */
uint8_t mode;
/** \brief The PpsSource field. */
uint8_t ppsSource;
} GpsConfigurationRegister;
/** \brief Structure representing the GPS Solution - LLA register. */
typedef struct GpsSolutionLlaRegister{
/** \brief The Time field. */
double time;
/** \brief The Week field. */
uint16_t week;
/** \brief The GpsFix field. */
uint8_t gpsFix;
/** \brief The NumSats field. */
uint8_t numSats;
/** \brief The Lla field. */
vec3d lla;
/** \brief The NedVel field. */
vec3f nedVel;
/** \brief The NedAcc field. */
vec3f nedAcc;
/** \brief The SpeedAcc field. */
float speedAcc;
/** \brief The TimeAcc field. */
float timeAcc;
/** \brief The Constructor for GPS LLA Solution. */
GpsSolutionLlaRegister(){
time = 0.0;
week = 0;
gpsFix = 0;
numSats = 0;
speedAcc = 0.0;
timeAcc = 0.0;
}
};
const uint16_t GpsSolutionLlaRegisterID = 58;
/** \brief Structure representing the GPS Solution - ECEF register. */
typedef struct {
/** \brief The Tow field. */
double tow;
/** \brief The Week field. */
uint16_t week;
/** \brief The GpsFix field. */
uint8_t gpsFix;
/** \brief The NumSats field. */
uint8_t numSats;
/** \brief The Position field. */
vec3d position;
/** \brief The Velocity field. */
vec3f velocity;
/** \brief The PosAcc field. */
vec3f posAcc;
/** \brief The SpeedAcc field. */
float speedAcc;
/** \brief The TimeAcc field. */
float timeAcc;
} GpsSolutionEcefRegister;
typedef struct InsSolutionLla {
const uint16_t InsSolutionLlaRegisterID = 64;
/** \brief Structure representing the INS Solution - LLA register. */
typedef struct Register {
/** \brief The Time field. */
double time;
/** \brief The Week field. */
uint16_t week;
/** \brief The Status field. */
uint16_t status;
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The Position field. */
vec3d position;
/** \brief The NedVel field. */
vec3f nedVel;
/** \brief The AttUncertainty field. */
float attUncertainty;
/** \brief The PosUncertainty field. */
float posUncertainty;
/** \brief The VelUncertainty field. */
float velUncertainty;
InsSolutionLlaRegister(){
time = 0.0;
week = 0;
status = 0;
attUncertainty = 0.0;
posUncertainty = 0.0;
}
};
};
/** \brief Structure representing the INS Solution - ECEF register. */
typedef struct {
/** \brief The Time field. */
double time;
/** \brief The Week field. */
uint16_t week;
/** \brief The Status field. */
uint16_t status;
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The Position field. */
vec3d position;
/** \brief The Velocity field. */
vec3f velocity;
/** \brief The AttUncertainty field. */
float attUncertainty;
/** \brief The PosUncertainty field. */
float posUncertainty;
/** \brief The VelUncertainty field. */
float velUncertainty;
} InsSolutionEcefRegister;
/** \brief Structure representing the INS Basic Configuration register for a VN-200 sensor. */
typedef struct {
/** \brief The Scenario field. */
uint8_t scenario;
/** \brief The AhrsAiding field. */
uint8_t ahrsAiding;
} InsBasicConfigurationRegisterVn200;
/** \brief Structure representing the INS Basic Configuration register for a VN-300 sensor. */
typedef struct {
/** \brief The Scenario field. */
uint8_t scenario;
/** \brief The AhrsAiding field. */
uint8_t ahrsAiding;
/** \brief The EstBaseline field. */
uint8_t estBaseline;
} InsBasicConfigurationRegisterVn300;
/** \brief Structure representing the INS Advanced Configuration register. */
typedef struct {
/** \brief The UseMag field. */
uint8_t useMag;
/** \brief The UsePres field. */
uint8_t usePres;
/** \brief The PosAtt field. */
uint8_t posAtt;
/** \brief The VelAtt field. */
uint8_t velAtt;
/** \brief The VelBias field. */
uint8_t velBias;
/** \brief The UseFoam field. */
uint8_t useFoam;
/** \brief The GPSCovType field. */
uint8_t gpsCovType;
/** \brief The VelCount field. */
uint8_t velCount;
/** \brief The VelInit field. */
float velInit;
/** \brief The MoveOrigin field. */
float moveOrigin;
/** \brief The GPSTimeout field. */
float gpsTimeout;
/** \brief The DeltaLimitPos field. */
float deltaLimitPos;
/** \brief The DeltaLimitVel field. */
float deltaLimitVel;
/** \brief The MinPosUncertainty field. */
float minPosUncertainty;
/** \brief The MinVelUncertainty field. */
float minVelUncertainty;
} InsAdvancedConfigurationRegister;
/** \brief Structure representing the INS State - LLA register. */
typedef struct {
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The Position field. */
vec3d position;
/** \brief The Velocity field. */
vec3f velocity;
/** \brief The Accel field. */
vec3f accel;
/** \brief The AngularRate field. */
vec3f angularRate;
} InsStateLlaRegister;
/** \brief Structure representing the INS State - ECEF register. */
typedef struct {
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The Position field. */
vec3d position;
/** \brief The Velocity field. */
vec3f velocity;
/** \brief The Accel field. */
vec3f accel;
/** \brief The AngularRate field. */
vec3f angularRate;
} InsStateEcefRegister;
/** \brief Structure representing the Startup Filter Bias Estimate register. */
typedef struct {
/** \brief The GyroBias field. */
vec3f gyroBias;
/** \brief The AccelBias field. */
vec3f accelBias;
/** \brief The PressureBias field. */
float pressureBias;
} StartupFilterBiasEstimateRegister;
/** \brief Structure representing the Delta Theta and Delta Velocity register. */
typedef struct {
/** \brief The DeltaTime field. */
float deltaTime;
/** \brief The DeltaTheta field. */
vec3f deltaTheta;
/** \brief The DeltaVelocity field. */
vec3f deltaVelocity;
} DeltaThetaAndDeltaVelocityRegister;
/** \brief Structure representing the Delta Theta and Delta Velocity Configuration register. */
typedef struct {
/** \brief The IntegrationFrame field. */
uint8_t integrationFrame;
/** \brief The GyroCompensation field. */
uint8_t gyroCompensation;
/** \brief The AccelCompensation field. */
uint8_t accelCompensation;
} DeltaThetaAndDeltaVelocityConfigurationRegister;
/** \brief Structure representing the Reference Vector Configuration register. */
typedef struct {
/** \brief The UseMagModel field. */
uint8_t useMagModel;
/** \brief The UseGravityModel field. */
uint8_t useGravityModel;
/** \brief The RecalcThreshold field. */
uint32_t recalcThreshold;
/** \brief The Year field. */
float year;
/** \brief The Position field. */
vec3d position;
} ReferenceVectorConfigurationRegister;
/** \brief Structure representing the Gyro Compensation register. */
typedef struct {
/** \brief The C field. */
mat3f c;
/** \brief The B field. */
vec3f b;
} GyroCompensationRegister;
/** \brief Structure representing the IMU Filtering Configuration register. */
typedef struct {
/** \brief The MagWindowSize field. */
uint16_t magWindowSize;
/** \brief The AccelWindowSize field. */
uint16_t accelWindowSize;
/** \brief The GyroWindowSize field. */
uint16_t gyroWindowSize;
/** \brief The TempWindowSize field. */
uint16_t tempWindowSize;
/** \brief The PresWindowSize field. */
uint16_t presWindowSize;
/** \brief The MagFilterMode field. */
uint8_t magFilterMode;
/** \brief The AccelFilterMode field. */
uint8_t accelFilterMode;
/** \brief The GyroFilterMode field. */
uint8_t gyroFilterMode;
/** \brief The TempFilterMode field. */
uint8_t tempFilterMode;
/** \brief The PresFilterMode field. */
uint8_t presFilterMode;
} ImuFilteringConfigurationRegister;
/** \brief Structure representing the GPS Compass Baseline register. */
typedef struct {
/** \brief The Position field. */
vec3f position;
/** \brief The Uncertainty field. */
vec3f uncertainty;
} GpsCompassBaselineRegister;
/** \brief Structure representing the GPS Compass Estimated Baseline register. */
typedef struct {
/** \brief The EstBaselineUsed field. */
uint8_t estBaselineUsed;
/** \brief The NumMeas field. */
uint16_t numMeas;
/** \brief The Position field. */
vec3f position;
/** \brief The Uncertainty field. */
vec3f uncertainty;
} GpsCompassEstimatedBaselineRegister;
/** \brief Structure representing the IMU Rate Configuration register. */
typedef struct {
/** \brief The imuRate field. */
uint16_t imuRate;
/** \brief The NavDivisor field. */
uint16_t navDivisor;
/** \brief The filterTargetRate field. */
float filterTargetRate;
/** \brief The filterMinRate field. */
float filterMinRate;
} ImuRateConfigurationRegister;
/** \brief Structure representing the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register. */
typedef struct {
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The BodyAccel field. */
vec3f bodyAccel;
/** \brief The Gyro field. */
vec3f gyro;
} YawPitchRollTrueBodyAccelerationAndAngularRatesRegister;
const uint16_t YawPitchRollTrueBodyAccelerationAndAngularRatesRegisterID = 239;
/** \brief Structure representing the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates register. */
typedef struct {
/** \brief The YawPitchRoll field. */
vec3f yawPitchRoll;
/** \brief The InertialAccel field. */
vec3f inertialAccel;
/** \brief The Gyro field. */
vec3f gyro;
} YawPitchRollTrueInertialAccelerationAndAngularRatesRegister;
#ifdef __cplusplus
}
}
#endif
#ifdef _WIN32
#pragma warning(pop)
#endif
#endif