OSVR-Core
OrientationState.h
Go to the documentation of this file.
1 
11 // Copyright 2015 Sensics, Inc.
12 //
13 // Licensed under the Apache License, Version 2.0 (the "License");
14 // you may not use this file except in compliance with the License.
15 // You may obtain a copy of the License at
16 //
17 // http://www.apache.org/licenses/LICENSE-2.0
18 //
19 // Unless required by applicable law or agreed to in writing, software
20 // distributed under the License is distributed on an "AS IS" BASIS,
21 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 // See the License for the specific language governing permissions and
23 // limitations under the License.
24 
25 #ifndef INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA
26 #define INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA
27 
28 // Internal Includes
29 #include "FlexibleKalmanBase.h"
30 #include "ExternalQuaternion.h"
31 
32 // Library/third-party includes
33 #include <Eigen/Core>
34 #include <Eigen/Geometry>
35 
36 // Standard includes
37 // - none
38 
39 namespace osvr {
40 namespace kalman {
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;
47 
48  using StateSquareMatrix = types::DimSquareMatrix<Dimension>;
49 
52  inline StateVectorBlock3 incrementalOrientation(StateVector &vec) {
53  return vec.head<3>();
54  }
55  inline ConstStateVectorBlock3
56  incrementalOrientation(StateVector const &vec) {
57  return vec.head<3>();
58  }
59 
60  inline StateVectorBlock3 angularVelocity(StateVector &vec) {
61  return vec.tail<3>();
62  }
63  inline ConstStateVectorBlock3 angularVelocity(StateVector const &vec) {
64  return vec.tail<3>();
65  }
67 
71  StateSquareMatrix A = StateSquareMatrix::Identity();
72  A.topRightCorner<3, 3>() = types::SquareMatrix<3>::Identity() * dt;
73  return A;
74  }
75  inline StateSquareMatrix
76  stateTransitionMatrixWithVelocityDamping(double dt, double damping) {
77 
78  // eq. 4.5 in Welch 1996
79 
80  auto A = stateTransitionMatrix(dt);
81  auto attenuation = std::pow(damping, dt);
82  A.bottomRightCorner<3, 3>() *= attenuation;
83  return A;
84  }
86  inline StateVector applyVelocity(StateVector const &state, double dt) {
87  // eq. 4.5 in Welch 1996
88 
91 
92  StateVector ret = state;
93  incrementalOrientation(ret) += angularVelocity(state) * dt;
94  return ret;
95  }
96 
97  inline void dampenVelocities(StateVector &state, double damping,
98  double dt) {
99  auto attenuation = std::pow(damping, dt);
100  angularVelocity(state) *= attenuation;
101  }
102 
103  inline Eigen::Quaterniond
104  incrementalOrientationToQuat(StateVector const &state) {
105  return external_quat::vecToQuat(incrementalOrientation(state));
106  }
107 
108  class State : public HasDimension<6> {
109  public:
110  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
111 
114  : m_state(StateVector::Zero()),
115  m_errorCovariance(
117  Identity() ),
118  m_orientation(Eigen::Quaterniond::Identity()) {}
120  void setStateVector(StateVector const &state) { m_state = state; }
122  StateVector const &stateVector() const { return m_state; }
123  // set P
124  void setErrorCovariance(StateSquareMatrix const &errorCovariance) {
125  m_errorCovariance = errorCovariance;
126  }
129  return m_errorCovariance;
130  }
131 
133  void setQuaternion(Eigen::Quaterniond const &quaternion) {
134  m_orientation = quaternion.normalized();
135  }
136 
137  void postCorrect() { externalizeRotation(); }
138 
139  void externalizeRotation() {
140  m_orientation = getCombinedQuaternion();
141  incrementalOrientation(m_state) = Eigen::Vector3d::Zero();
142  }
143 
144  void normalizeQuaternion() { m_orientation.normalize(); }
145 
146  StateVectorBlock3 angularVelocity() {
147  return orient_externalized_rotation::angularVelocity(m_state);
148  }
149 
150  ConstStateVectorBlock3 angularVelocity() const {
151  return orient_externalized_rotation::angularVelocity(m_state);
152  }
153 
154  Eigen::Quaterniond const &getQuaternion() const {
155  return m_orientation;
156  }
157 
160  return (incrementalOrientationToQuat(m_state) * m_orientation)
161  .normalized();
162  }
163 
164  private:
168  StateVector m_state;
170  StateSquareMatrix m_errorCovariance;
172  Eigen::Quaterniond m_orientation;
173  };
174 
177  template <typename OutputStream>
178  inline OutputStream &operator<<(OutputStream &os, State const &state) {
179  os << "State:" << state.stateVector().transpose() << "\n";
180  os << "quat:" << state.getCombinedQuaternion().coeffs().transpose()
181  << "\n";
182  os << "error:\n" << state.errorCovariance() << "\n";
183  return os;
184  }
185  } // namespace orient_externalized_rotation
186 } // namespace kalman
187 } // namespace osvr
188 
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&#39;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