libfovis
Public Member Functions | Static Public Member Functions | List of all members
VisualOdometry Class Reference

Main visual odometry class. More...

Public Member Functions

bool getChangeReferenceFrames () const
 
int getFastThreshold () const
 
const Eigen::Matrix3d & getInitialHomography () const
 
const Eigen::Isometry3d & getMotionEstimate () const
 
const Eigen::MatrixXd & getMotionEstimateCov () const
 
MotionEstimateStatusCode getMotionEstimateStatus () const
 
const MotionEstimatorgetMotionEstimator () const
 
const VisualOdometryOptionsgetOptions () const
 
const Eigen::Isometry3d & getPose ()
 
const OdometryFramegetReferenceFrame () const
 
const OdometryFramegetTargetFrame () const
 
void processFrame (const uint8_t *gray, DepthSource *depth_source)
 
void sanityCheck () const
 
 VisualOdometry (const Rectification *rectification, const VisualOdometryOptions &options)
 

Static Public Member Functions

static VisualOdometryOptions getDefaultOptions ()
 

Detailed Description

Main visual odometry class.

#include <fovis/fovis.hpp>

This is the primary fovis class for estimating visual odometry. To use it, you'll need three things:

A typical use case for the VisualOdometry class is to repeatedly call processFrame() as new image data is available, which estimates the camera motion and makes the resulting estimation data available via accessor methods.

Options to control the behavior of the visual odometry algorithm can be passed in to the constructor using a VisualOdometryOptions object.

Constructor & Destructor Documentation

VisualOdometry ( const Rectification rectification,
const VisualOdometryOptions options 
)

Constructs a new visual odometry estimator.

Parameters
rectificationspecifies the input image dimensions, as well as the mapping from input image coordinates to rectified image coordinates.
optionscontrols the behavior of the estimation algorithms. This is specified as a key/value dictionary.

Member Function Documentation

void processFrame ( const uint8_t *  gray,
DepthSource depth_source 
)

process an input image and estimate the 3D camera motion between gray and the frame previously passed to this method. The estimated motion for the very first frame will always be the identity transform.

Parameters
graya new input image. The image dimensions must match those passed in to the constructor, and the image data must be stored in row-major order, with no pad bytes between rows. An internal copy of the image is made, and the input data is no longer needed once this method returns.
depth_sourcea source of depth information that can either provide a depth estimate at each pixel of the input image, or report that no depth estimate is available.
const Eigen::Isometry3d& getPose ( )
inline

Retrieves the integrated pose estimate. On initialization, the camera is positioned at the origin, with +Z pointing along the camera look vector, +X to the right, and +Y down.

const OdometryFrame* getReferenceFrame ( ) const
inline

Retrieve the current reference frame used for motion estimation. The reference frame will not change as long as new input frames are easily matched to it.

const OdometryFrame* getTargetFrame ( ) const
inline

Retrieve the current target frame used for motion estimation.

bool getChangeReferenceFrames ( ) const
inline

If this returns true, then the current target frame will become the reference frame on the next call to processFrame().

MotionEstimateStatusCode getMotionEstimateStatus ( ) const
inline
Returns
whether motion estimation succeeded on the most recent call to processFrame(), or provides a rough failure reason.
const Eigen::Isometry3d& getMotionEstimate ( ) const
inline
Returns
the estimated camera motion from the previous frame to the current frame.
const Eigen::MatrixXd& getMotionEstimateCov ( ) const
inline
Returns
the covariance matrix resulting from the final nonlinear least-squares motion estimation step.
const MotionEstimator* getMotionEstimator ( ) const
inline
Returns
the MotionEstimator object used internally.
int getFastThreshold ( ) const
inline
Returns
the threshold used by the FAST feature detector.
const Eigen::Matrix3d& getInitialHomography ( ) const
inline
Returns
the 2D homography computed during initial rotation estimation.
const VisualOdometryOptions& getOptions ( ) const
inline
Returns
the options passed in to the constructor.
static VisualOdometryOptions getDefaultOptions ( )
static
Returns
a reasonable set of default options that can be passed in to the constructor if you don't know or care about the options.
void sanityCheck ( ) const

Performs some internal sanity checks and aborts the program on failure. This is for debugging only.


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