OSVR Framework (Internal Development Docs)  0.6-1962-g59773924
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
osvr::vbtracker::TrackingSystem Class Reference

Classes

struct  Impl
 Private implementation structure for TrackingSystem. More...
 

Public Member Functions

ConfigParams const & getParams () const
 
void setUseIMU (bool useIMU)
 
bool haveCameraPose () const
 
void setCameraPose (Eigen::Isometry3d const &camPose)
 
Eigen::Isometry3d const & getCameraPose () const
 This gets rTc - the pose of the camera in the room.
 
Eigen::Isometry3d const & getRoomToCamera () const
 
bool isRoomCalibrationComplete ()
 
void calibrationHandleIMUData (BodyId id, util::time::TimeValue const &tv, Eigen::Quaterniond const &quat)
 
Setup and Teardown
 TrackingSystem (ConfigParams const &params)
 
 ~TrackingSystem ()
 
TrackedBodycreateTrackedBody ()
 
Runtime methods

Perform the initial phase of image processing. This does not modify the bodies, so it can happen in parallel/background processing. It's also the most expensive, so that's handy.

ImageOutputDataPtr performInitialImageProcessing (util::time::TimeValue const &tv, cv::Mat const &frame, cv::Mat const &frameGray, CameraParameters const &camParams)
 
LedUpdateCount const & updateLedsFromVideoData (ImageOutputDataPtr &&imageData)
 
BodyIndices const & updateBodiesFromVideoData (ImageOutputDataPtr &&imageData)
 
BodyIndices const & processFrame (util::time::TimeValue const &tv, cv::Mat const &frame, cv::Mat const &frameGray, CameraParameters const &camParams)
 
Accessors
std::size_t getNumBodies () const
 
bool isValidBodyId (BodyId i) const
 
TrackedBodygetBody (BodyId i)
 
TrackedBody const & getBody (BodyId i) const
 
TrackedBodyTargetgetTarget (BodyTargetId target)
 
TrackedBodyTarget const * getTarget (BodyTargetId target) const
 

Friends

class TrackingDebugDisplay
 

Detailed Description

Definition at line 54 of file TrackingSystem.h.

Member Function Documentation

LedUpdateCount const & osvr::vbtracker::TrackingSystem::updateLedsFromVideoData ( ImageOutputDataPtr &&  imageData)

This is the second phase of the video-based tracking algorithm - the part that actually changes LED state.

Parameters
imageDataOutput from the first step - please std::move() the output of the first step into this step.

If you don't require updated poses, you can stop after this step, not proceeding to the third and final phase, and still keep track of which beacons are which.

Returns
a reference to an internal map of body IDs to counts of used LED measurements for debugging.

Clear internal data, we're invalidating things here.

Update our frame cache, since we're taking ownership of the image data now.

Go through each target and try to process the measurements.

Definition at line 90 of file TrackingSystem.cpp.

BodyIndices const & osvr::vbtracker::TrackingSystem::updateBodiesFromVideoData ( ImageOutputDataPtr &&  imageData)

The combined second and third phases of the video-based tracking algorithm. The third phase uses the updated LED data stored in each target to arrive at updated pose estimates.

These two phases are combined in one call to ensure preconditions - it would be invalid to call the third phase without immediately previously calling this second phase, but no state handover needs to take place.

Parameters
imageDataOutput from the first step - please std::move() the output of the first step into this step.
Returns
A reference to a vector of body indices that were updated with this latest frame.

Do the second phase of stuff

Do the third phase of tracking.

Trigger debug display, if activated.

Definition at line 115 of file TrackingSystem.cpp.

BodyIndices const& osvr::vbtracker::TrackingSystem::processFrame ( util::time::TimeValue const &  tv,
cv::Mat const &  frame,
cv::Mat const &  frameGray,
CameraParameters const &  camParams 
)
inline

All parts of the tracking algorithm combined for convenience.

Returns
A reference to a vector of body indices that were updated with this latest frame.

Definition at line 107 of file TrackingSystem.h.

ConfigParams const& osvr::vbtracker::TrackingSystem::getParams ( ) const
inline
Todo:
refactor;

Definition at line 132 of file TrackingSystem.h.

void osvr::vbtracker::TrackingSystem::setUseIMU ( bool  useIMU)
inline
Todo:
just for debugging

Definition at line 135 of file TrackingSystem.h.

Eigen::Isometry3d const & osvr::vbtracker::TrackingSystem::getRoomToCamera ( ) const

This gets cTr - the inverse of the camera pose, transforms from the room coordinate system to the camera coordinate system.

Definition at line 233 of file TrackingSystem.cpp.

bool osvr::vbtracker::TrackingSystem::isRoomCalibrationComplete ( )
Todo:
should just be able to do this by checking the state of the calibrator.

If this is true, we know it's true. If it's false, we must go check.

Update the cached value.

Definition at line 237 of file TrackingSystem.cpp.

void osvr::vbtracker::TrackingSystem::calibrationHandleIMUData ( BodyId  id,
util::time::TimeValue const &  tv,
Eigen::Quaterniond const &  quat 
)

Called by TrackedBody::incorporateNewMeasurementFromIMU() if room calibration is not complete.

Definition at line 212 of file TrackingSystem.cpp.


The documentation for this class was generated from the following files: