0.3.0
Loading...
Searching...
No Matches
NAV::VectorNavSensor Class Reference

Vector Nav Sensor Class. More...

Classes

struct  BinaryGroupData
 Needed data to display a binary group in the GUI. More...
 
struct  TimeSync
 Information needed to sync Master/Slave sensors. More...
 

Public Member Functions

void guiConfig () override
 ImGui config window which is shown on double click.
 
VectorNavSensoroperator= (const VectorNavSensor &)=delete
 Copy assignment operator.
 
VectorNavSensoroperator= (VectorNavSensor &&)=delete
 Move assignment operator.
 
bool resetNode () override
 Resets the node. It is guaranteed that the node is initialized when this is called.
 
void restore (const json &j) override
 Restores the node from a json object.
 
json save () const override
 Saves the node into a json object.
 
std::string type () const override
 String representation of the Class Type.
 
 VectorNavSensor ()
 Default constructor.
 
 VectorNavSensor (const VectorNavSensor &)=delete
 Copy constructor.
 
 VectorNavSensor (VectorNavSensor &&)=delete
 Move constructor.
 
 ~VectorNavSensor () override
 Destructor.
 
- Public Member Functions inherited from NAV::Imu
 Imu (const Imu &)=delete
 Copy constructor.
 
 Imu (Imu &&)=delete
 Move constructor.
 
const ImuPosimuPosition () const
 Position and rotation information for conversion from platform to body frame.
 
Imuoperator= (const Imu &)=delete
 Copy assignment operator.
 
Imuoperator= (Imu &&)=delete
 Move assignment operator.
 
 ~Imu () override=default
 Destructor.
 
- Public Member Functions inherited from NAV::Node
virtual void afterCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link was established.
 
virtual void afterDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link was deleted.
 
bool doDeinitialize (bool wait=false)
 Asks the node worker to deinitialize the node.
 
bool doDisable (bool wait=false)
 Asks the node worker to disable the node.
 
bool doEnable ()
 Enable the node.
 
bool doInitialize (bool wait=false)
 Asks the node worker to initialize the node.
 
bool doReinitialize (bool wait=false)
 Asks the node worker to reinitialize the node.
 
virtual void flush ()
 Function called by the flow executer after finishing to flush out remaining data.
 
template<typename T >
std::optional< InputPin::IncomingLink::ValueWrapper< T > > getInputValue (size_t portIndex) const
 Get Input Value connected on the pin. Only const data types.
 
Mode getMode () const
 Get the current mode of the node.
 
const ImVec2 & getSize () const
 Get the size of the node.
 
State getState () const
 Get the current state of the node.
 
InputPininputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
 
size_t inputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
 
void invokeCallbacks (size_t portIndex, const std::shared_ptr< const NodeData > &data)
 Calls all registered callbacks on the specified output port.
 
bool isDisabled () const
 Checks if the node is disabled.
 
bool isInitialized () const
 Checks if the node is initialized.
 
bool isOnlyRealtime () const
 Checks if the node is only working in real time (sensors, network interfaces, ...)
 
bool isTransient () const
 Checks if the node is changing its state currently.
 
std::string nameId () const
 Node name and id.
 
 Node (const Node &)=delete
 Copy constructor.
 
 Node (Node &&)=delete
 Move constructor.
 
 Node (std::string name)
 Constructor.
 
void notifyOutputValueChanged (size_t pinIdx, const InsTime &insTime, const std::scoped_lock< std::mutex > &guard)
 Notifies connected nodes about the change.
 
virtual bool onCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link is to be established.
 
virtual void onDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link is to be deleted.
 
Nodeoperator= (const Node &)=delete
 Copy assignment operator.
 
Nodeoperator= (Node &&)=delete
 Move assignment operator.
 
OutputPinoutputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
 
size_t outputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
 
void releaseInputValue (size_t portIndex)
 Unblocks the connected node. Has to be called when the input value should be released and getInputValue was not called.
 
std::scoped_lock< std::mutex > requestOutputValueLock (size_t pinIdx)
 Blocks the thread till the output values was read by all connected nodes.
 
virtual void restoreAtferLink (const json &j)
 Restores link related properties of the node from a json object.
 
void wakeWorker ()
 Wakes the worker thread.
 
virtual ~Node ()
 Destructor.
 
- Public Member Functions inherited from NAV::UartSensor
UartSensoroperator= (const UartSensor &)=delete
 Copy assignment operator.
 
UartSensoroperator= (UartSensor &&)=delete
 Move assignment operator.
 
 UartSensor (const UartSensor &)=delete
 Copy constructor.
 
 UartSensor (UartSensor &&)=delete
 Move constructor.
 
 ~UartSensor ()=default
 Destructor.
 

Static Public Member Functions

static std::string category ()
 String representation of the Class Category.
 
static std::string typeStatic ()
 String representation of the Class Type.
 
- Static Public Member Functions inherited from NAV::Node
static std::string toString (State state)
 Converts the state into a printable text.
 

Private Types

enum class  BinaryRegisterMerge : uint8_t {
  None ,
  Output1_Output2 ,
  Output1_Output3 ,
  Output2_Output3
}
 Possible Merge combinations between the binary output registers. More...
 
enum class  VectorNavModel : uint8_t {
  VN100_VN110 ,
  VN310
}
 VectorNav Model enumeration. More...
 

Private Member Functions

void deinitialize () override
 Deinitialize the node.
 
bool initialize () override
 Initialize the node.
 

Static Private Member Functions

static void asciiOrBinaryAsyncMessageReceived (void *userData, vn::protocol::uart::Packet &p, size_t index)
 Callback handler for notifications of new asynchronous data packets received.
 
static void coupleImuFilterRates (NAV::VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &binaryField)
 Updates the ImuFilter's rate when pressing the checkbox button.
 
static void mergeVectorNavBinaryObservations (const std::shared_ptr< VectorNavBinaryOutput > &target, const std::shared_ptr< VectorNavBinaryOutput > &source)
 Merges the content of the two observations into one.
 

Private Attributes

ScrollingBuffer< std::string > _asciiOutputBuffer
 Buffer to store Ascii Output Messages.
 
int _asciiOutputBufferSize
 Max size of the Ascii Output.
 
uint32_t _asyncDataOutputFrequency
 Async Data Output Frequency Register.
 
int _asyncDataOutputFrequencySelected
 Selected Frequency of the Async Ascii Output in the GUI.
 
vn::protocol::uart::AsciiAsync _asyncDataOutputType
 Async Data Output Type Register.
 
std::array< vn::sensors::BinaryOutputRegister, 3 > _binaryOutputRegister
 Binary Output Register 1 - 3.
 
BinaryRegisterMerge _binaryOutputRegisterMerge
 Merge binary output registers together. This has to be done because VectorNav sensors have a buffer overflow when packages get too big.
 
size_t _binaryOutputRegisterMergeIndex
 Index of the binary output for the merge observation stored.
 
std::shared_ptr< VectorNavBinaryOutput_binaryOutputRegisterMergeObservation
 First observation received, which should be merged together.
 
std::array< size_t, 3 > _binaryOutputSelectedFrequency
 Selected Frequency of the Binary Outputs in the GUI.
 
vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister
 Communication Protocol Control.
 
std::string _connectedSensorPort
 Connected sensor port.
 
bool _coupleImuRateOutput
 Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor)
 
vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister
 Delta Theta and Delta Velocity Configuration.
 
std::pair< std::vector< uint16_t >, std::vector< std::string > > _dividerFrequency
 First: List of RateDividers, Second: List of Matching Frequencies.
 
vn::math::vec3f _filterStartupGyroBias
 Filter Startup Gyro Bias.
 
struct { 
 
   InsTime   lastGnssTime 
 Last GNSS time received.
 
   uint64_t   timeSinceStartup 
 Time since startup when the GNSS time was received.
 
_gnssTimeCounter 
 Last received GNSS time.
 
vn::math::vec3f _gpsAntennaOffset
 GNSS Antenna A Offset.
 
vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister
 GNSS Compass Baseline.
 
vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister
 GNSS Configuration.
 
vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister
 IMU Filtering Configuration.
 
vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300
 INS Basic Configuration.
 
std::array< InsTime, 3 > _lastMessageTime
 Stores the time of the last received message.
 
std::array< uint64_t, 3 > _lastMessageTimeSinceStartup
 Stores the time of the last received message.
 
vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister
 Magnetic and Gravity Reference Vectors.
 
vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister
 Magnetometer Calibration Control.
 
vn::math::mat3f _referenceFrameRotationMatrix
 Reference Frame Rotation.
 
vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister
 Reference Vector Configuration.
 
VectorNavModel _sensorModel
 The sensor model which is selected in the GUI.
 
vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister
 Startup Filter Bias Estimate.
 
vn::sensors::SynchronizationControlRegister _synchronizationControlRegister
 Synchronization Control.
 
bool _syncInPin
 Show the SyncIn Pin.
 
TimeSync _timeSyncOut
 Time synchronization for master sensors.
 
vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister
 Velocity Compensation Control.
 
vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister
 VPE Accelerometer Basic Tuning.
 
vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister
 VPE Basic Control.
 
vn::sensors::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister
 VPE Gyro Basic Tuning.
 
vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister
 VPE Magnetometer Basic Tuning.
 
vn::sensors::VnSensor _vs
 VnSensor Object.
 

Static Private Attributes

static const std::array< BinaryGroupData, 9 > _binaryGroupAttitude
 Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solution.
 
static const std::array< BinaryGroupData, 16 > _binaryGroupGNSS
 Binary group 4 provides all outputs which are dependent upon the measurements collected from the primary onboard, Binary group 7 from the secondary onboard GNSS, or external GNSS (if enabled).
 
static const std::array< BinaryGroupData, 11 > _binaryGroupIMU
 Binary group 3 provides all outputs which are dependent upon the measurements collected from the onboard IMU, or an external IMU (if enabled).
 
static const std::array< BinaryGroupData, 11 > _binaryGroupINS
 Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution.
 
static const std::array< BinaryGroupData, 10 > _binaryGroupTime
 Binary group 1 contains a wide assortment of commonly used data required for most applications.
 
static constexpr std::array _possibleAsyncDataOutputFrequency
 Possible values for the Async Data Output Frequency Register.
 
static constexpr double IMU_DEFAULT_FREQUENCY
 Internal Frequency of the Sensor.
 
static constexpr size_t OUTPUT_PORT_INDEX_ASCII_OUTPUT
 Flow (StringObs)
 

Friends

class NAV::VectorNavFile
 

Additional Inherited Members

- Public Types inherited from NAV::Node
enum class  Mode : uint8_t {
  REAL_TIME ,
  POST_PROCESSING
}
 Different Modes the Node can work in. More...
 
enum class  State : uint8_t {
  Disabled ,
  Deinitialized ,
  DoInitialize ,
  Initializing ,
  Initialized ,
  DoDeinitialize ,
  Deinitializing ,
  DoShutdown ,
  Shutdown
}
 Possible states of the node. More...
 
- Public Types inherited from NAV::UartSensor
enum  Baudrate : uint32_t {
  BAUDRATE_FASTEST ,
  BAUDRATE_9600 ,
  BAUDRATE_19200 ,
  BAUDRATE_38400 ,
  BAUDRATE_57600 ,
  BAUDRATE_115200 ,
  BAUDRATE_128000 ,
  BAUDRATE_230400 ,
  BAUDRATE_460800 ,
  BAUDRATE_921600
}
 Available Baudrates. More...
 
- Public Attributes inherited from NAV::Node
bool callbacksEnabled
 Enables the callbacks.
 
ax::NodeEditor::NodeId id
 Unique Id of the Node.
 
std::vector< InputPininputPins
 List of input pins.
 
Kind kind
 Kind of the Node.
 
std::string name
 Name of the Node.
 
std::vector< OutputPinoutputPins
 List of output pins.
 
std::multimap< InsTime, std::pair< OutputPin *, size_t > > pollEvents
 Map with callback events (sorted by time)
 
- Protected Member Functions inherited from NAV::Imu
 Imu (std::string name)
 Constructor.
 
- Protected Member Functions inherited from NAV::UartSensor
void restore (const json &j)
 Restores the node from a json object.
 
json save () const
 Saves the node into a json object.
 
Baudrate sensorBaudrate () const
 Returns the Baudrate for the element Selected by the GUI.
 
 UartSensor ()=default
 Default constructor.
 
- Static Protected Member Functions inherited from NAV::UartSensor
static int baudrate2Selection (Baudrate baud)
 Returns the guiSelection for the given baudrate.
 
- Protected Attributes inherited from NAV::Imu
ImuPos _imuPos
 Position and rotation information for conversion from platform to body frame.
 
- Protected Attributes inherited from NAV::Node
ImVec2 _guiConfigDefaultWindowSize
 
bool _hasConfig
 Flag if the config window should be shown.
 
bool _lockConfigDuringRun
 Lock the config when executing post-processing.
 
bool _onlyRealTime
 Whether the node can run in post-processing or only real-time.
 
- Protected Attributes inherited from NAV::UartSensor
int _selectedBaudrate
 Baudrate for the sensor.
 
std::string _sensorPort
 

Detailed Description

Vector Nav Sensor Class.

Member Enumeration Documentation

◆ BinaryRegisterMerge

enum class NAV::VectorNavSensor::BinaryRegisterMerge : uint8_t
strongprivate

Possible Merge combinations between the binary output registers.

Enumerator
None 

Do not merge any outputs.

Output1_Output2 

Merge Output 1 and 2.

Output1_Output3 

Merge Output 1 and 3.

Output2_Output3 

Merge Output 2 and 3.

◆ VectorNavModel

enum class NAV::VectorNavSensor::VectorNavModel : uint8_t
strongprivate

VectorNav Model enumeration.

Enumerator
VN100_VN110 

VN-100/SMD (Miniature, lightweight and high-performance IMU & AHRS) VN-110/E (Rugged and Miniature Tactical-Grade IMU and AHRS)

VN310 

VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass)

Member Function Documentation

◆ asciiOrBinaryAsyncMessageReceived()

static void NAV::VectorNavSensor::asciiOrBinaryAsyncMessageReceived ( void * userData,
vn::protocol::uart::Packet & p,
size_t index )
staticprivate

Callback handler for notifications of new asynchronous data packets received.

Parameters
[in,out]userDataPointer to the data we supplied when we called registerAsyncPacketReceivedHandler
[in]pEncapsulation of the data packet. At this state, it has already been validated and identified as an asynchronous data message
[in]indexAdvanced usage item and can be safely ignored for now

◆ coupleImuFilterRates()

static void NAV::VectorNavSensor::coupleImuFilterRates ( NAV::VectorNavSensor * sensor,
vn::sensors::BinaryOutputRegister & bor,
uint32_t & binaryField )
staticprivate

Updates the ImuFilter's rate when pressing the checkbox button.

Parameters
sensorVectorNav sensor (VN100, VN310E, etc.)
borBinary Output Register
binaryFieldBinary Field

◆ deinitialize()

void NAV::VectorNavSensor::deinitialize ( )
overrideprivatevirtual

Deinitialize the node.

Reimplemented from NAV::Node.

◆ guiConfig()

void NAV::VectorNavSensor::guiConfig ( )
overridevirtual

ImGui config window which is shown on double click.

Attention
Don't forget to set _hasConfig to true in the constructor of the node

Reimplemented from NAV::Imu.

◆ initialize()

bool NAV::VectorNavSensor::initialize ( )
overrideprivatevirtual

Initialize the node.

Reimplemented from NAV::Node.

◆ mergeVectorNavBinaryObservations()

static void NAV::VectorNavSensor::mergeVectorNavBinaryObservations ( const std::shared_ptr< VectorNavBinaryOutput > & target,
const std::shared_ptr< VectorNavBinaryOutput > & source )
staticprivate

Merges the content of the two observations into one.

Parameters
[in,out]targetThe observation used to store the merged information
[in]sourceThe observation where information is taken from

◆ resetNode()

bool NAV::VectorNavSensor::resetNode ( )
overridevirtual

Resets the node. It is guaranteed that the node is initialized when this is called.

Reimplemented from NAV::Node.

◆ restore()

void NAV::VectorNavSensor::restore ( const json & j)
overridevirtual

Restores the node from a json object.

Parameters
[in]jJson object with the node state

Reimplemented from NAV::Imu.

◆ save()

json NAV::VectorNavSensor::save ( ) const
nodiscardoverridevirtual

Saves the node into a json object.

Reimplemented from NAV::Imu.

◆ type()

std::string NAV::VectorNavSensor::type ( ) const
nodiscardoverridevirtual

String representation of the Class Type.

Implements NAV::Node.

Member Data Documentation

◆ _asyncDataOutputFrequency

uint32_t NAV::VectorNavSensor::_asyncDataOutputFrequency
private

Async Data Output Frequency Register.

Note
See User manual VN-310 - 8.2.8 (p 94) / VN-100 - 5.2.8 (p 66)

◆ _asyncDataOutputType

vn::protocol::uart::AsciiAsync NAV::VectorNavSensor::_asyncDataOutputType
private

Async Data Output Type Register.

Note
See User manual VN-310 - 8.2.7 (p 92f) / VN-100 - 5.2.7 (p 65)

◆ _binaryGroupAttitude

const std::array<BinaryGroupData, 9> NAV::VectorNavSensor::_binaryGroupAttitude
staticprivate

Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solution.

The attitude will be derived from either the AHRS or the INS, depending upon which filter is currently active and tracking. All of the fields in this group will only be valid if the AHRS/INS filter is currently enabled and tracking.

◆ _binaryGroupGNSS

const std::array<BinaryGroupData, 16> NAV::VectorNavSensor::_binaryGroupGNSS
staticprivate

Binary group 4 provides all outputs which are dependent upon the measurements collected from the primary onboard, Binary group 7 from the secondary onboard GNSS, or external GNSS (if enabled).

All data in this group is updated at the rate of the GNSS receiver (nominally 5Hz for the internal GNSS).

Note
If data is asynchronously sent from group 4/7 at a rate equal to the GNSS update rate, then packets will be sent out when updated by the GNSS receiver. For all other rates, the output will be based on the divisor selected and the internal IMU sampling rate.

◆ _binaryGroupINS

const std::array<BinaryGroupData, 11> NAV::VectorNavSensor::_binaryGroupINS
staticprivate

Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution.

All of the fields in this group will only be valid if the INS filter is currently enabled and tracking.

◆ _binaryGroupTime

const std::array<BinaryGroupData, 10> NAV::VectorNavSensor::_binaryGroupTime
staticprivate

Binary group 1 contains a wide assortment of commonly used data required for most applications.

All of the outputs found in group 1 are also present in the other groups. In this sense, group 1 is a subset of commonly used outputs from the other groups. This simplifies the configuration of binary output messages for applications that only require access to the commonly used data found in group 1. For these applications you can hard code the group field to 1, and not worry about implemented support for the other binary groups. Using group 1 for commonly used outputs also has the advantage of reducing the overall packet size, since the packet length is dependent upon the number of binary groups active.

Binary group 2 provides all timing and event counter related outputs.

Some of these outputs (such as the TimeGps, TimePps, and TimeUtc), require either that the internal GNSS to be enabled, or an external GNSS must be present.

◆ _binaryOutputRegister

std::array<vn::sensors::BinaryOutputRegister, 3> NAV::VectorNavSensor::_binaryOutputRegister
private

Binary Output Register 1 - 3.

This register allows the user to construct a custom binary output message that contains a collection of desired estimated states and sensor measurements.

Note
See User manual VN-310 - 8.2.11-13 (p 100ff) / VN-100 - 5.2.11-13 (p 73ff)

◆ _communicationProtocolControlRegister

vn::sensors::CommunicationProtocolControlRegister NAV::VectorNavSensor::_communicationProtocolControlRegister
private

Communication Protocol Control.

Contains parameters that controls the communication protocol used by the sensor.

Note
See User manual VN-310 - 8.2.10 (p 97ff) / VN-100 - 5.2.10 (p 69ff)

◆ _deltaThetaAndDeltaVelocityConfigurationRegister

vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister NAV::VectorNavSensor::_deltaThetaAndDeltaVelocityConfigurationRegister
private

Delta Theta and Delta Velocity Configuration.

This register contains configuration options for the internal coning/sculling calculations.

Note
See User manual VN-310 - 9.2.6 (p 116) / VN-100 - 6.2.6 (p 87)

◆ _filterStartupGyroBias

vn::math::vec3f NAV::VectorNavSensor::_filterStartupGyroBias
private

Filter Startup Gyro Bias.

The filter gyro bias estimate used at startup.

Note
See User manual VN-100 - 7.3.4 (p 107)

◆ _gpsAntennaOffset

vn::math::vec3f NAV::VectorNavSensor::_gpsAntennaOffset
private

GNSS Antenna A Offset.

Configures the position offset of GNSS antenna A from the VN-310E in the vehicle reference frame.

Note
See User manual VN-310 - 10.2.2 (p 125)

◆ _gpsCompassBaselineRegister

vn::sensors::GpsCompassBaselineRegister NAV::VectorNavSensor::_gpsCompassBaselineRegister
private

GNSS Compass Baseline.

Configures the position offset and measurement uncertainty of the second GNSS antenna relative to the first GNSS antenna in the vehicle reference frame.

Note
See User manual VN-310 - 10.2.3 (p 126f)

◆ _gpsConfigurationRegister

vn::sensors::GpsConfigurationRegister NAV::VectorNavSensor::_gpsConfigurationRegister
private

GNSS Configuration.

Note
See User manual VN-310 - 10.2.1 (p 124)

◆ _imuFilteringConfigurationRegister

vn::sensors::ImuFilteringConfigurationRegister NAV::VectorNavSensor::_imuFilteringConfigurationRegister
private

IMU Filtering Configuration.

Controls the level of filtering performed on the raw IMU measurements.

Note
See User manual VN-310 - 9.2.5 (p 115) / VN-100 - 6.2.5 (p 86)

◆ _insBasicConfigurationRegisterVn300

vn::sensors::InsBasicConfigurationRegisterVn300 NAV::VectorNavSensor::_insBasicConfigurationRegisterVn300
private

INS Basic Configuration.

Note
See User manual VN-310 - 12.3.1 (p 166)

◆ _magneticAndGravityReferenceVectorsRegister

vn::sensors::MagneticAndGravityReferenceVectorsRegister NAV::VectorNavSensor::_magneticAndGravityReferenceVectorsRegister
private

Magnetic and Gravity Reference Vectors.

Magnetic and gravity reference vectors.

Note
See User manual VN-310 - 14.1.1 (p 175) / VN-100 - 9.1.1 (p 115)

◆ _magnetometerCalibrationControlRegister

vn::sensors::MagnetometerCalibrationControlRegister NAV::VectorNavSensor::_magnetometerCalibrationControlRegister
private

Magnetometer Calibration Control.

Controls the magnetometer real-time calibration algorithm.

Note
See User manual VN-310 - 13.1.1 (p 169) / VN-100 - 8.1.1 (p 110)

◆ _possibleAsyncDataOutputFrequency

std::array NAV::VectorNavSensor::_possibleAsyncDataOutputFrequency
staticconstexprprivate

Possible values for the Async Data Output Frequency Register.

Note
See User manual VN-310 - 8.2.8 (p 94) / VN-100 - 5.2.8 (p 66)

◆ _referenceFrameRotationMatrix

vn::math::mat3f NAV::VectorNavSensor::_referenceFrameRotationMatrix
private

Reference Frame Rotation.

Allows the measurements of the VN-310E to be rotated into a different reference frame.

Note
See User manual VN-310 - 9.2.4 (p 114) / VN-100 - 6.2.4 (p 85)

◆ _referenceVectorConfigurationRegister

vn::sensors::ReferenceVectorConfigurationRegister NAV::VectorNavSensor::_referenceVectorConfigurationRegister
private

Reference Vector Configuration.

Control register for both the onboard world magnetic and gravity model corrections.

Note
See User manual VN-310 - 14.1.2 (p 176) / VN-100 - 9.1.2 (p 116)

◆ _startupFilterBiasEstimateRegister

vn::sensors::StartupFilterBiasEstimateRegister NAV::VectorNavSensor::_startupFilterBiasEstimateRegister
private

Startup Filter Bias Estimate.

Sets the initial estimate for the filter bias states.

Note
See User manual VN-310 - 12.3.2 (p 167)

◆ _synchronizationControlRegister

vn::sensors::SynchronizationControlRegister NAV::VectorNavSensor::_synchronizationControlRegister
private

Synchronization Control.

Contains parameters which allow the timing of the VN-310E to be synchronized with external devices.

Note
See User manual VN-310 - 8.2.9 (p 95f) / VN-100 - 5.2.9 (p 67f)

◆ _velocityCompensationControlRegister

vn::sensors::VelocityCompensationControlRegister NAV::VectorNavSensor::_velocityCompensationControlRegister
private

Velocity Compensation Control.

Provides control over the velocity compensation feature for the attitude filter.

Note
See User manual VN-100 - 10.2.1 (p 123)

◆ _vpeAccelerometerBasicTuningRegister

vn::sensors::VpeAccelerometerBasicTuningRegister NAV::VectorNavSensor::_vpeAccelerometerBasicTuningRegister
private

VPE Accelerometer Basic Tuning.

Provides basic control of the adaptive filtering and tuning for the accelerometer.

Note
See User manual VN-100 - 7.3.3 (p 106)

◆ _vpeBasicControlRegister

vn::sensors::VpeBasicControlRegister NAV::VectorNavSensor::_vpeBasicControlRegister
private

VPE Basic Control.

Provides control over various features relating to the onboard attitude filtering algorithm.

Note
See User manual VN-310 - 11.3.1 (p 158) / VN-100 - 7.3.1 (p 104)

◆ _vpeGyroBasicTuningRegister

vn::sensors::VpeGyroBasicTuningRegister NAV::VectorNavSensor::_vpeGyroBasicTuningRegister
private

VPE Gyro Basic Tuning.

Provides basic control of the adaptive filtering and tuning for the gyro.

Note
See User manual VN-100 - 7.3.5 (p 108)

◆ _vpeMagnetometerBasicTuningRegister

vn::sensors::VpeMagnetometerBasicTuningRegister NAV::VectorNavSensor::_vpeMagnetometerBasicTuningRegister
private

VPE Magnetometer Basic Tuning.

Provides basic control of the adaptive filtering and tuning for the magnetometer..

Note
See User manual VN-100 - 7.3.2 (p 105)

The documentation for this class was generated from the following file: