#include </home/jenkins/root/workspace/OSVR-Core-Docs/plugins/videoimufusion/VideoIMUFusion.h>
Classes | |
class | RunningData |
class | StartupData |
Public Member Functions | |
VideoIMUFusion (VideoIMUFusionParams const ¶ms=VideoIMUFusionParams()) | |
Constructor. | |
~VideoIMUFusion () | |
Out-of-line destructor required for unique_ptr pimpl idiom. | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void | handleIMUData (const OSVR_TimeValue ×tamp, const OSVR_OrientationReport &report) |
void | handleIMUVelocity (const OSVR_TimeValue ×tamp, const Eigen::Vector3d &angVel) |
void | handleVideoTrackerDataWhileRunning (const OSVR_TimeValue ×tamp, const OSVR_PoseReport &report) |
void | handleVideoTrackerDataDuringStartup (const OSVR_TimeValue ×tamp, const OSVR_PoseReport &report, const OSVR_OrientationState &orientation) |
bool | running () const |
OSVR_PoseState const & | getLatestPose () const |
Returns the latest (fusion result, if available) pose. | |
osvr::util::time::TimeValue const & | getLatestTime () const |
OSVR_VelocityState const & | getLatestVelocity () const |
osvr::util::time::TimeValue const & | getLatestVelocityTime () const |
OSVR_PoseState const & | getLatestReorientedVideoPose () const |
OSVR_PoseState const & | getLatestCameraPose () const |
Eigen::Matrix< double, 12, 12 > const & | getErrorCovariance () const |
The core of the fusion code - doesn't deal with getting data in or reporting it out, for easier use in testing.
Definition at line 43 of file VideoIMUFusion.h.
void VideoIMUFusion::handleIMUData | ( | const OSVR_TimeValue & | timestamp, |
const OSVR_OrientationReport & | report | ||
) |
Call with each new IMU report, whether or not fusion is in running state.
Definition at line 103 of file VideoIMUFusion.cpp.
void VideoIMUFusion::handleIMUVelocity | ( | const OSVR_TimeValue & | timestamp, |
const Eigen::Vector3d & | angVel | ||
) |
Arbitrary, chosen to avoid aliasing
Just report the angular velocity
Definition at line 118 of file VideoIMUFusion.cpp.
void VideoIMUFusion::handleVideoTrackerDataWhileRunning | ( | const OSVR_TimeValue & | timestamp, |
const OSVR_PoseReport & | report | ||
) |
Call with each new video tracker report once we've entered running state.
Definition at line 153 of file VideoIMUFusion.cpp.
void VideoIMUFusion::handleVideoTrackerDataDuringStartup | ( | const OSVR_TimeValue & | timestamp, |
const OSVR_PoseReport & | report, | ||
const OSVR_OrientationState & | orientation | ||
) |
Call with each new video tracker report, as well as the most recent IMU orientation state, while the filter has not yet entered running state.
The IMU state is required to compute a filtered estimate of the position/orientation of the camera relative to the room and IMU
Definition at line 262 of file VideoIMUFusion.cpp.
|
inline |
Returns the timestamp associated with the latest (fusion result, if available) pose.
Definition at line 79 of file VideoIMUFusion.h.
|
inline |
Returns the latest video-tracker pose, re-oriented to be in room space. Only valid once running state is entered!
Definition at line 92 of file VideoIMUFusion.h.
|
inline |
Returns the latest pose of the camera in the room. Only valid once running state is entered!
Currently constant once running state is entered.
Definition at line 101 of file VideoIMUFusion.h.
Eigen::Matrix< double, 12, 12 > const & VideoIMUFusion::getErrorCovariance | ( | ) | const |
Returns the current state error covariance matrix Only valid once running state is entered!
Definition at line 70 of file VideoIMUFusion.cpp.