Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes
fovis::VisualOdometry Class Reference

Main visual odometry class. More...

#include <visual_odometry.hpp>

List of all members.

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)
 ~VisualOdometry ()

Static Public Member Functions

static VisualOdometryOptions getDefaultOptions ()

Private Member Functions

Eigen::Quaterniond estimateInitialRotation (const OdometryFrame *prev, const OdometryFrame *cur, const Eigen::Isometry3d &init_motion_estimate=Eigen::Isometry3d::Identity())
void prepareFrame (OdometryFrame *frame)

Private Attributes

bool _change_reference_frames
OdometryFrame_cur_frame
MotionEstimator_estimator
int _fast_threshold
float _fast_threshold_adaptive_gain
int _fast_threshold_max
int _fast_threshold_min
int _feature_window_size
long _frame_count
int _initial_rotation_pyramid_level
int _num_pyramid_levels
VisualOdometryOptions _options
VisualOdometryPriv_p
OdometryFrame_prev_frame
const Rectification_rectification
OdometryFrame_ref_frame
int _ref_frame_change_threshold
int _target_pixels_per_feature
bool _use_adaptive_threshold
bool _use_homography_initialization

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.

Definition at line 67 of file visual_odometry.hpp.


Constructor & Destructor Documentation

fovis::VisualOdometry::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.

Definition at line 57 of file visual_odometry.cpp.

Definition at line 107 of file visual_odometry.cpp.


Member Function Documentation

Eigen::Quaterniond fovis::VisualOdometry::estimateInitialRotation ( const OdometryFrame prev,
const OdometryFrame cur,
const Eigen::Isometry3d &  init_motion_estimate = Eigen::Isometry3d::Identity() 
) [private]

Definition at line 124 of file visual_odometry.cpp.

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

Definition at line 128 of file visual_odometry.hpp.

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.

Definition at line 297 of file visual_odometry.cpp.

Returns:
the threshold used by the FAST feature detector.

Definition at line 166 of file visual_odometry.hpp.

const Eigen::Matrix3d& fovis::VisualOdometry::getInitialHomography ( ) const [inline]
Returns:
the 2D homography computed during initial rotation estimation.

Definition at line 173 of file visual_odometry.hpp.

const Eigen::Isometry3d& fovis::VisualOdometry::getMotionEstimate ( ) const [inline]
Returns:
the estimated camera motion from the previous frame to the current frame.

Definition at line 144 of file visual_odometry.hpp.

const Eigen::MatrixXd& fovis::VisualOdometry::getMotionEstimateCov ( ) const [inline]
Returns:
the covariance matrix resulting from the final nonlinear least-squares motion estimation step.

Definition at line 152 of file visual_odometry.hpp.

Returns:
whether motion estimation succeeded on the most recent call to processFrame(), or provides a rough failure reason.

Definition at line 136 of file visual_odometry.hpp.

Returns:
the MotionEstimator object used internally.

Definition at line 159 of file visual_odometry.hpp.

Returns:
the options passed in to the constructor.

Definition at line 180 of file visual_odometry.hpp.

const Eigen::Isometry3d& fovis::VisualOdometry::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.

Definition at line 104 of file visual_odometry.hpp.

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.

Definition at line 113 of file visual_odometry.hpp.

Retrieve the current target frame used for motion estimation.

Definition at line 120 of file visual_odometry.hpp.

void fovis::VisualOdometry::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.

Definition at line 170 of file visual_odometry.cpp.

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

Definition at line 282 of file visual_odometry.cpp.


Member Data Documentation

Definition at line 215 of file visual_odometry.hpp.

Definition at line 209 of file visual_odometry.hpp.

Definition at line 211 of file visual_odometry.hpp.

Definition at line 226 of file visual_odometry.hpp.

Definition at line 232 of file visual_odometry.hpp.

Definition at line 230 of file visual_odometry.hpp.

Definition at line 229 of file visual_odometry.hpp.

Definition at line 221 of file visual_odometry.hpp.

Definition at line 217 of file visual_odometry.hpp.

Definition at line 242 of file visual_odometry.hpp.

Definition at line 223 of file visual_odometry.hpp.

Definition at line 244 of file visual_odometry.hpp.

Definition at line 213 of file visual_odometry.hpp.

Definition at line 208 of file visual_odometry.hpp.

Definition at line 205 of file visual_odometry.hpp.

Definition at line 207 of file visual_odometry.hpp.

Definition at line 239 of file visual_odometry.hpp.

Definition at line 231 of file visual_odometry.hpp.

Definition at line 234 of file visual_odometry.hpp.

Definition at line 235 of file visual_odometry.hpp.


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


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12