|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | State () |
| Default constructor.
|
|
void | setStateVector (StateVector const &state) |
| set xhat
|
|
StateVector const & | stateVector () const |
| xhat
|
|
void | setErrorCovariance (StateSquareMatrix const &errorCovariance) |
|
StateSquareMatrix const & | errorCovariance () const |
| P.
|
|
StateSquareMatrix & | errorCovariance () |
|
void | setQuaternion (Eigen::Quaterniond const &quaternion) |
| Intended for startup use.
|
|
void | postCorrect () |
|
void | externalizeRotation () |
|
StateVectorBlock3 | position () |
|
ConstStateVectorBlock3 | position () const |
|
StateVectorBlock3 | incrementalOrientation () |
|
ConstStateVectorBlock3 | incrementalOrientation () const |
|
StateVectorBlock3 | velocity () |
|
ConstStateVectorBlock3 | velocity () const |
|
StateVectorBlock3 | angularVelocity () |
|
ConstStateVectorBlock3 | angularVelocity () const |
|
Eigen::Quaterniond const & | getQuaternion () const |
|
Eigen::Quaterniond | getCombinedQuaternion () const |
|
Eigen::Isometry3d | getIsometry () const |
|
Definition at line 164 of file PoseState.h.
Eigen::Quaterniond osvr::kalman::pose_externalized_rotation::State::getCombinedQuaternion |
( |
| ) |
const |
|
inline |
- Todo:
- is just quat multiplication OK here? Order right?
Definition at line 238 of file PoseState.h.
Eigen::Isometry3d osvr::kalman::pose_externalized_rotation::State::getIsometry |
( |
| ) |
const |
|
inline |
Get the position and quaternion combined into a single isometry (transformation)
Definition at line 246 of file PoseState.h.
The documentation for this class was generated from the following file: