OSVR-Core
PoseStateExponentialMap.h
Go to the documentation of this file.
1 
15 // Copyright 2015 Sensics, Inc.
16 //
17 // Licensed under the Apache License, Version 2.0 (the "License");
18 // you may not use this file except in compliance with the License.
19 // You may obtain a copy of the License at
20 //
21 // http://www.apache.org/licenses/LICENSE-2.0
22 //
23 // Unless required by applicable law or agreed to in writing, software
24 // distributed under the License is distributed on an "AS IS" BASIS,
25 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
26 // See the License for the specific language governing permissions and
27 // limitations under the License.
28 
29 #ifndef INCLUDED_PoseStateExponentialMap_h_GUID_3D1B779A_6DBE_4993_0AE7_C28344E55A51
30 #define INCLUDED_PoseStateExponentialMap_h_GUID_3D1B779A_6DBE_4993_0AE7_C28344E55A51
31 
32 // Internal Includes
33 #include "FlexibleKalmanBase.h"
34 #include "MatrixExponentialMap.h"
35 
36 // Library/third-party includes
37 // - none
38 
39 // Standard includes
40 // - none
41 
42 namespace osvr {
43 namespace kalman {
44  namespace pose_exp_map {
45 
46  using Dimension = types::DimensionConstant<12>;
47  using StateVector = types::DimVector<Dimension>;
48  using StateVectorBlock3 = StateVector::FixedSegmentReturnType<3>::Type;
49  using ConstStateVectorBlock3 =
50  StateVector::ConstFixedSegmentReturnType<3>::Type;
51 
52  using StateVectorBlock6 = StateVector::FixedSegmentReturnType<6>::Type;
53  using StateSquareMatrix = types::DimSquareMatrix<Dimension>;
54 
57  inline StateVectorBlock3 position(StateVector &vec) {
58  return vec.head<3>();
59  }
60  inline ConstStateVectorBlock3 position(StateVector const &vec) {
61  return vec.head<3>();
62  }
63 
64  inline StateVectorBlock3 orientation(StateVector &vec) {
65  return vec.segment<3>(3);
66  }
67  inline ConstStateVectorBlock3 orientation(StateVector const &vec) {
68  return vec.segment<3>(3);
69  }
70 
71  inline StateVectorBlock3 velocity(StateVector &vec) {
72  return vec.segment<3>(6);
73  }
74  inline ConstStateVectorBlock3 velocity(StateVector const &vec) {
75  return vec.segment<3>(6);
76  }
77 
78  inline StateVectorBlock3 angularVelocity(StateVector &vec) {
79  return vec.segment<3>(9);
80  }
81  inline ConstStateVectorBlock3 angularVelocity(StateVector const &vec) {
82  return vec.segment<3>(9);
83  }
84 
86  inline StateVectorBlock6 velocities(StateVector &vec) {
87  return vec.segment<6>(6);
88  }
90 
93  inline StateSquareMatrix stateTransitionMatrix(double dt) {
94  // eq. 4.5 in Welch 1996 - except we have all the velocities at the
95  // end
96  StateSquareMatrix A = StateSquareMatrix::Identity();
97  A.topRightCorner<6, 6>() = types::SquareMatrix<6>::Identity() * dt;
98 
99  return A;
100  }
101  inline double computeAttenuation(double damping, double dt) {
102  return std::pow(damping, dt);
103  }
104  inline StateSquareMatrix
105  stateTransitionMatrixWithVelocityDamping(double dt, double damping) {
106 
107  // eq. 4.5 in Welch 1996
108 
109  auto A = stateTransitionMatrix(dt);
110  auto attenuation = computeAttenuation(damping, dt);
111  A.bottomRightCorner<6, 6>() *= attenuation;
112  return A;
113  }
115  inline StateVector applyVelocity(StateVector const &state, double dt) {
116  // eq. 4.5 in Welch 1996
117 
120 
121  StateVector ret = state;
122  position(ret) += velocity(state) * dt;
123  orientation(ret) += angularVelocity(state) * dt;
124  return ret;
125  }
126 
127  inline void dampenVelocities(StateVector &state, double damping,
128  double dt) {
129  auto attenuation = computeAttenuation(damping, dt);
130  velocities(state) *= attenuation;
131  }
132  class State : public HasDimension<12> {
133  public:
134  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
135 
138  : m_state(StateVector::Zero()),
139  m_errorCovariance(
141  Identity() ) {}
143  void setStateVector(StateVector const &state) { m_state = state; }
145  StateVector const &stateVector() const { return m_state; }
146  // set P
147  void setErrorCovariance(StateSquareMatrix const &errorCovariance) {
148  m_errorCovariance = errorCovariance;
149  }
152  return m_errorCovariance;
153  }
154 
155  void postCorrect() {
157  orientation(m_state));
158  m_cacheData.reset(Eigen::Vector3d(orientation(m_state)));
159  }
160 
161  StateVectorBlock3 position() {
162  return pose_exp_map::position(m_state);
163  }
164 
165  ConstStateVectorBlock3 position() const {
166  return pose_exp_map::position(m_state);
167  }
168 
169  Eigen::Quaterniond const &getQuaternion() {
170  return m_cacheData.getQuaternion();
171  }
172  Eigen::Matrix3d const &getRotationMatrix() {
173  return m_cacheData.getRotationMatrix();
174  }
175 
176  StateVectorBlock3 velocity() {
177  return pose_exp_map::velocity(m_state);
178  }
179 
180  ConstStateVectorBlock3 velocity() const {
181  return pose_exp_map::velocity(m_state);
182  }
183 
184  StateVectorBlock3 angularVelocity() {
185  return pose_exp_map::angularVelocity(m_state);
186  }
187 
188  ConstStateVectorBlock3 angularVelocity() const {
189  return pose_exp_map::angularVelocity(m_state);
190  }
191 
192  private:
195  StateVector m_state;
197  StateSquareMatrix m_errorCovariance;
198 
201  };
202 
205  template <typename OutputStream>
206  inline OutputStream &operator<<(OutputStream &os, State const &state) {
207  os << "State:" << state.stateVector().transpose() << "\n";
208  os << "error:\n" << state.errorCovariance() << "\n";
209  return os;
210  }
211  } // namespace pose_exp_map
212 } // namespace kalman
213 } // namespace osvr
214 #endif // INCLUDED_PoseStateExponentialMap_h_GUID_3D1B779A_6DBE_4993_0AE7_C28344E55A51
StateVector const & stateVector() const
xhat
Definition: PoseStateExponentialMap.h:145
typename detail::Dimension_impl< T >::type Dimension
Given a state or measurement, get the dimension as a std::integral_constant.
Definition: FlexibleKalmanBase.h:87
Convenience base class for things (like states and measurements) that have a dimension.
Definition: FlexibleKalmanBase.h:63
void avoidSingularities(T &&omega)
Adjust a matrix exponential map rotation vector, if required, to avoid singularities.
Definition: MatrixExponentialMap.h:80
The main namespace for all C++ elements of the framework, internal and external.
Definition: namespace_osvr.dox:3
Contained cached computed values.
Definition: MatrixExponentialMap.h:108
Definition: PoseStateExponentialMap.h:132
EIGEN_MAKE_ALIGNED_OPERATOR_NEW State()
Default constructor.
Definition: PoseStateExponentialMap.h:137
void setStateVector(StateVector const &state)
set xhat
Definition: PoseStateExponentialMap.h:143
Eigen::Matrix3d const & getRotationMatrix()
Converts a rotation vector to a rotation matrix: Uses Rodrigues&#39; formula, and the first two terms of ...
Definition: MatrixExponentialMap.h:201
Definition: Quaternion.h:47
StateSquareMatrix const & errorCovariance() const
P.
Definition: PoseStateExponentialMap.h:151
void reset(Eigen::MatrixBase< Derived > const &omega)
Definition: MatrixExponentialMap.h:168
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:127