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) {
70 inline StateSquareMatrix stateTransitionMatrix(
double dt) {
71 StateSquareMatrix A = StateSquareMatrix::Identity();
72 A.topRightCorner<3, 3>() = types::SquareMatrix<3>::Identity() * dt;
75 inline StateSquareMatrix
76 stateTransitionMatrixWithVelocityDamping(
double dt,
double damping) {
80 auto A = stateTransitionMatrix(dt);
81 auto attenuation = std::pow(damping, dt);
82 A.bottomRightCorner<3, 3>() *= attenuation;
86 inline StateVector applyVelocity(StateVector
const &state,
double dt) {
92 StateVector ret = state;
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;
103 inline Eigen::Quaterniond
104 incrementalOrientationToQuat(StateVector
const &state) {
105 return external_quat::vecToQuat(incrementalOrientation(state));
110 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
114 : m_state(StateVector::Zero()),
118 m_orientation(
Eigen::Quaterniond::Identity()) {}
129 return m_errorCovariance;
134 m_orientation = quaternion.normalized();
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);
154 Eigen::Quaterniond
const &getQuaternion()
const {
155 return m_orientation;
160 return (incrementalOrientationToQuat(m_state) * m_orientation)
170 StateSquareMatrix m_errorCovariance;
172 Eigen::Quaterniond m_orientation;
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()
182 os <<
"error:\n" << state.errorCovariance() <<
"\n";
189 #endif // INCLUDED_OrientationState_h_GUID_B2EA5856_0B18_43B1_CE18_8B7385E607CA
typename detail::Dimension_impl< T >::type Dimension
void setQuaternion(Eigen::Quaterniond const &quaternion)
Intended for startup use.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW State()
Default constructor.
void setStateVector(StateVector const &state)
set xhat
StateVector const & stateVector() const
xhat
Eigen::Quaterniond getCombinedQuaternion() const
StateSquareMatrix const & errorCovariance() const
P.