29 #ifndef INCLUDED_PoseStateExponentialMap_h_GUID_3D1B779A_6DBE_4993_0AE7_C28344E55A51 30 #define INCLUDED_PoseStateExponentialMap_h_GUID_3D1B779A_6DBE_4993_0AE7_C28344E55A51 44 namespace pose_exp_map {
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;
52 using StateVectorBlock6 = StateVector::FixedSegmentReturnType<6>::Type;
53 using StateSquareMatrix = types::DimSquareMatrix<Dimension>;
57 inline StateVectorBlock3 position(StateVector &vec) {
60 inline ConstStateVectorBlock3 position(StateVector
const &vec) {
64 inline StateVectorBlock3 orientation(StateVector &vec) {
65 return vec.segment<3>(3);
67 inline ConstStateVectorBlock3 orientation(StateVector
const &vec) {
68 return vec.segment<3>(3);
71 inline StateVectorBlock3 velocity(StateVector &vec) {
72 return vec.segment<3>(6);
74 inline ConstStateVectorBlock3 velocity(StateVector
const &vec) {
75 return vec.segment<3>(6);
78 inline StateVectorBlock3 angularVelocity(StateVector &vec) {
79 return vec.segment<3>(9);
81 inline ConstStateVectorBlock3 angularVelocity(StateVector
const &vec) {
82 return vec.segment<3>(9);
87 return vec.segment<6>(6);
101 inline double computeAttenuation(
double damping,
double dt) {
102 return std::pow(damping, dt);
105 stateTransitionMatrixWithVelocityDamping(
double dt,
double damping) {
109 auto A = stateTransitionMatrix(dt);
110 auto attenuation = computeAttenuation(damping, dt);
111 A.bottomRightCorner<6, 6>() *= attenuation;
122 position(ret) += velocity(state) * dt;
123 orientation(ret) += angularVelocity(state) * dt;
127 inline void dampenVelocities(
StateVector &state,
double damping,
129 auto attenuation = computeAttenuation(damping, dt);
130 velocities(state) *= attenuation;
134 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
152 return m_errorCovariance;
157 orientation(m_state));
158 m_cacheData.
reset(Eigen::Vector3d(orientation(m_state)));
161 StateVectorBlock3 position() {
162 return pose_exp_map::position(m_state);
165 ConstStateVectorBlock3 position()
const {
166 return pose_exp_map::position(m_state);
170 return m_cacheData.getQuaternion();
172 Eigen::Matrix3d
const &getRotationMatrix() {
176 StateVectorBlock3 velocity() {
177 return pose_exp_map::velocity(m_state);
180 ConstStateVectorBlock3 velocity()
const {
181 return pose_exp_map::velocity(m_state);
184 StateVectorBlock3 angularVelocity() {
185 return pose_exp_map::angularVelocity(m_state);
188 ConstStateVectorBlock3 angularVelocity()
const {
189 return pose_exp_map::angularVelocity(m_state);
205 template <
typename OutputStream>
206 inline OutputStream &operator<<(OutputStream &os,
State const &state) {
207 os <<
"State:" << state.
stateVector().transpose() <<
"\n";
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' 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