OSVR-Core
Classes | Namespaces | Typedefs | Functions
OrientationState.h File Reference

Header. More...

#include "FlexibleKalmanBase.h"
#include "ExternalQuaternion.h"
#include <Eigen/Core>
#include <Eigen/Geometry>

Go to the source code of this file.

Classes

class  osvr::kalman::orient_externalized_rotation::State
 

Namespaces

 osvr
 The main namespace for all C++ elements of the framework, internal and external.
 
 osvr::kalman
 Header-only framework for building Kalman-style filters, prediction, and sensor fusion.
 

Typedefs

using osvr::kalman::orient_externalized_rotation::Dimension = types::DimensionConstant< 6 >
 
using osvr::kalman::orient_externalized_rotation::StateVector = types::DimVector< Dimension >
 
using osvr::kalman::orient_externalized_rotation::StateVectorBlock3 = StateVector::FixedSegmentReturnType< 3 >::Type
 
using osvr::kalman::orient_externalized_rotation::ConstStateVectorBlock3 = StateVector::ConstFixedSegmentReturnType< 3 >::Type
 
using osvr::kalman::orient_externalized_rotation::StateSquareMatrix = types::DimSquareMatrix< Dimension >
 

Functions

StateSquareMatrix osvr::kalman::orient_externalized_rotation::stateTransitionMatrix (double dt)
 This returns A(deltaT), though if you're just predicting xhat-, use applyVelocity() instead for performance. More...
 
StateSquareMatrix osvr::kalman::orient_externalized_rotation::stateTransitionMatrixWithVelocityDamping (double dt, double damping)
 
StateVector osvr::kalman::orient_externalized_rotation::applyVelocity (StateVector const &state, double dt)
 Computes A(deltaT)xhat(t-deltaT) More...
 
void osvr::kalman::orient_externalized_rotation::dampenVelocities (StateVector &state, double damping, double dt)
 
Eigen::Quaterniond osvr::kalman::orient_externalized_rotation::incrementalOrientationToQuat (StateVector const &state)
 
template<typename OutputStream >
OutputStream & osvr::kalman::orient_externalized_rotation::operator<< (OutputStream &os, State const &state)
 Stream insertion operator, for displaying the state of the state class. More...
 
Accessors to blocks in the state vector.
StateVectorBlock3 osvr::kalman::orient_externalized_rotation::incrementalOrientation (StateVector &vec)
 
ConstStateVectorBlock3 osvr::kalman::orient_externalized_rotation::incrementalOrientation (StateVector const &vec)
 
StateVectorBlock3 osvr::kalman::orient_externalized_rotation::angularVelocity (StateVector &vec)
 
ConstStateVectorBlock3 osvr::kalman::orient_externalized_rotation::angularVelocity (StateVector const &vec)
 

Detailed Description

Header.

Date
2015
Author
Sensics, Inc. http://sensics.com/osvr

Function Documentation

§ applyVelocity()

StateVector osvr::kalman::orient_externalized_rotation::applyVelocity ( StateVector const &  state,
double  dt 
)
inline

Computes A(deltaT)xhat(t-deltaT)

Todo:
benchmark - assuming for now that the manual small calcuations are faster than the matrix ones.

§ operator<<()

template<typename OutputStream >
OutputStream& osvr::kalman::orient_externalized_rotation::operator<< ( OutputStream &  os,
State const &  state 
)
inline

Stream insertion operator, for displaying the state of the state class.

§ stateTransitionMatrix()

StateSquareMatrix osvr::kalman::orient_externalized_rotation::stateTransitionMatrix ( double  dt)
inline

This returns A(deltaT), though if you're just predicting xhat-, use applyVelocity() instead for performance.