|
StateSquareMatrix | osvr::kalman::pose_externalized_rotation::stateTransitionMatrix (double dt) |
| This returns A(deltaT), though if you're just predicting xhat-, use applyVelocity() instead for performance. More...
|
|
double | osvr::kalman::pose_externalized_rotation::computeAttenuation (double damping, double dt) |
| Function used to compute the coefficient m in v_new = m * v_old. More...
|
|
StateSquareMatrix | osvr::kalman::pose_externalized_rotation::stateTransitionMatrixWithVelocityDamping (double dt, double damping) |
| Returns the state transition matrix for a constant velocity with a single damping parameter (not for direct use in computing state transition, because it is very sparse, but in computing other values)
|
|
StateSquareMatrix | osvr::kalman::pose_externalized_rotation::stateTransitionMatrixWithSeparateVelocityDamping (double dt, double posDamping, double oriDamping) |
| Returns the state transition matrix for a constant velocity with separate damping paramters for linear and angular velocity (not for direct use in computing state transition, because it is very sparse, but in computing other values)
|
|
StateVector | osvr::kalman::pose_externalized_rotation::applyVelocity (StateVector const &state, double dt) |
| Computes A(deltaT)xhat(t-deltaT) More...
|
|
void | osvr::kalman::pose_externalized_rotation::dampenVelocities (StateVector &state, double damping, double dt) |
| Dampen all 6 components of velocity by a single factor.
|
|
void | osvr::kalman::pose_externalized_rotation::separatelyDampenVelocities (StateVector &state, double posDamping, double oriDamping, double dt) |
| Separately dampen the linear and angular velocities.
|
|
Eigen::Quaterniond | osvr::kalman::pose_externalized_rotation::incrementalOrientationToQuat (StateVector const &state) |
|
template<typename OutputStream > |
OutputStream & | osvr::kalman::pose_externalized_rotation::operator<< (OutputStream &os, State const &state) |
| Stream insertion operator, for displaying the state of the state class. More...
|
|
|
StateVectorBlock3 | osvr::kalman::pose_externalized_rotation::position (StateVector &vec) |
|
ConstStateVectorBlock3 | osvr::kalman::pose_externalized_rotation::position (StateVector const &vec) |
|
StateVectorBlock3 | osvr::kalman::pose_externalized_rotation::incrementalOrientation (StateVector &vec) |
|
ConstStateVectorBlock3 | osvr::kalman::pose_externalized_rotation::incrementalOrientation (StateVector const &vec) |
|
StateVectorBlock3 | osvr::kalman::pose_externalized_rotation::velocity (StateVector &vec) |
|
ConstStateVectorBlock3 | osvr::kalman::pose_externalized_rotation::velocity (StateVector const &vec) |
|
StateVectorBlock3 | osvr::kalman::pose_externalized_rotation::angularVelocity (StateVector &vec) |
|
ConstStateVectorBlock3 | osvr::kalman::pose_externalized_rotation::angularVelocity (StateVector const &vec) |
|
StateVectorBlock6 | osvr::kalman::pose_externalized_rotation::velocities (StateVector &vec) |
| both translational and angular velocities
|
|