25 #ifndef INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA 26 #define INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA 34 #include <Eigen/Geometry> 41 namespace orient_externalized_rotation {
42 using Dimension = types::DimensionConstant<6>;
43 using StateVector = types::DimVector<Dimension>;
44 using StateVectorBlock3 = StateVector::FixedSegmentReturnType<3>::Type;
45 using ConstStateVectorBlock3 =
46 StateVector::ConstFixedSegmentReturnType<3>::Type;
48 using StateSquareMatrix = types::DimSquareMatrix<Dimension>;
52 inline StateVectorBlock3 incrementalOrientation(StateVector &vec) {
55 inline ConstStateVectorBlock3
56 incrementalOrientation(StateVector
const &vec) {
60 inline StateVectorBlock3 angularVelocity(StateVector &vec) {
63 inline ConstStateVectorBlock3 angularVelocity(StateVector
const &vec) {
76 stateTransitionMatrixWithVelocityDamping(
double dt,
double damping) {
81 auto attenuation = std::pow(damping, dt);
82 A.bottomRightCorner<3, 3>() *= attenuation;
93 incrementalOrientation(ret) += angularVelocity(state) * dt;
97 inline void dampenVelocities(
StateVector &state,
double damping,
99 auto attenuation = std::pow(damping, dt);
100 angularVelocity(state) *= attenuation;
104 incrementalOrientationToQuat(
StateVector const &state) {
105 return external_quat::vecToQuat(incrementalOrientation(state));
110 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
129 return m_errorCovariance;
137 void postCorrect() { externalizeRotation(); }
139 void externalizeRotation() {
141 incrementalOrientation(m_state) = Eigen::Vector3d::Zero();
144 void normalizeQuaternion() { m_orientation.
normalize(); }
146 StateVectorBlock3 angularVelocity() {
147 return orient_externalized_rotation::angularVelocity(m_state);
150 ConstStateVectorBlock3 angularVelocity()
const {
151 return orient_externalized_rotation::angularVelocity(m_state);
155 return m_orientation;
160 return (incrementalOrientationToQuat(m_state) * m_orientation)
177 template <
typename OutputStream>
178 inline OutputStream &operator<<(OutputStream &os,
State const &state) {
179 os <<
"State:" << state.
stateVector().transpose() <<
"\n";
189 #endif // INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA
typename detail::Dimension_impl< T >::type Dimension
Given a state or measurement, get the dimension as a std::integral_constant.
Definition: FlexibleKalmanBase.h:87
const Coefficients & coeffs() const
Definition: Quaternion.h:93
Convenience base class for things (like states and measurements) that have a dimension.
Definition: FlexibleKalmanBase.h:63
The main namespace for all C++ elements of the framework, internal and external.
Definition: namespace_osvr.dox:3
iterative scaling algorithm to equilibrate rows and column norms in matrices
Definition: TestIMU_Common.h:87
StateSquareMatrix stateTransitionMatrix(double dt)
This returns A(deltaT), though if you're just predicting xhat-, use applyVelocity() instead for perfo...
Definition: OrientationState.h:70
void setQuaternion(Eigen::Quaterniond const &quaternion)
Intended for startup use.
Definition: OrientationState.h:133
EIGEN_MAKE_ALIGNED_OPERATOR_NEW State()
Default constructor.
Definition: OrientationState.h:113
void setStateVector(StateVector const &state)
set xhat
Definition: OrientationState.h:120
Eigen::Quaterniond getCombinedQuaternion() const
Definition: OrientationState.h:158
void normalize()
Normalizes the quaternion *this.
Definition: Quaternion.h:151
StateVector applyVelocity(StateVector const &state, double dt)
Computes A(deltaT)xhat(t-deltaT)
Definition: OrientationState.h:86
Definition: Quaternion.h:47
Quaternion< double > Quaterniond
double precision quaternion type
Definition: Quaternion.h:211
StateSquareMatrix const & errorCovariance() const
P.
Definition: OrientationState.h:128
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:127
StateVector const & stateVector() const
xhat
Definition: OrientationState.h:122
Definition: OrientationState.h:108
Quaternion normalized() const
Definition: Quaternion.h:154