Public Member Functions | Private Member Functions | Private Attributes
fovis::MotionEstimator Class Reference

Does the heavy lifting for frame-to-frame motion estimation. More...

#include <motion_estimation.hpp>

List of all members.

Public Member Functions

void estimateMotion (OdometryFrame *reference_frame, OdometryFrame *target_frame, DepthSource *depth_source, const Eigen::Isometry3d &init_motion_est, const Eigen::MatrixXd &init_motion_cov)
const FeatureMatchgetMatches () const
double getMeanInlierReprojectionError () const
const Eigen::Isometry3d & getMotionEstimate () const
const Eigen::MatrixXd & getMotionEstimateCov () const
MotionEstimateStatusCode getMotionEstimateStatus () const
int getNumInliers () const
int getNumMatches () const
int getNumReprojectionFailures () const
bool isMotionEstimateValid () const
 MotionEstimator (const Rectification *rectification, const VisualOdometryOptions &options)
void sanityCheck () const
 ~MotionEstimator ()

Private Member Functions

void computeMaximallyConsistentClique ()
void computeReprojectionError ()
void estimateRigidBodyTransform ()
void matchFeatures (PyramidLevel *ref_level, PyramidLevel *target_level)
void refineMotionEstimate ()

Private Attributes

double _clique_inlier_threshold
DepthSource_depth_source
MotionEstimateStatusCode _estimate_status
double _inlier_max_reprojection_error
FeatureMatcher _matcher
FeatureMatch_matches
int _matches_capacity
double _max_feature_motion
double _max_mean_reprojection_error
double _mean_reprojection_error
int _min_features_for_valid_motion_estimate
Eigen::Isometry3d * _motion_estimate
Eigen::MatrixXd * _motion_estimate_covariance
int _num_frames
int _num_inliers
int _num_matches
int _num_reprojection_failures
int _num_tracks
const Rectification_rectification
OdometryFrame_ref_frame
OdometryFrame_target_frame
bool _update_target_features_with_refined
int _use_subpixel_refinement

Detailed Description

Does the heavy lifting for frame-to-frame motion estimation.

TODO

Definition at line 37 of file motion_estimation.hpp.


Constructor & Destructor Documentation

fovis::MotionEstimator::MotionEstimator ( const Rectification rectification,
const VisualOdometryOptions options 
)

Definition at line 39 of file motion_estimation.cpp.

Definition at line 72 of file motion_estimation.cpp.


Member Function Documentation

Definition at line 390 of file motion_estimation.cpp.

Definition at line 633 of file motion_estimation.cpp.

void fovis::MotionEstimator::estimateMotion ( OdometryFrame reference_frame,
OdometryFrame target_frame,
DepthSource depth_source,
const Eigen::Isometry3d &  init_motion_est,
const Eigen::MatrixXd &  init_motion_cov 
)

Definition at line 88 of file motion_estimation.cpp.

Definition at line 520 of file motion_estimation.cpp.

Definition at line 65 of file motion_estimation.hpp.

Definition at line 81 of file motion_estimation.hpp.

const Eigen::Isometry3d& fovis::MotionEstimator::getMotionEstimate ( ) const [inline]

Definition at line 57 of file motion_estimation.hpp.

const Eigen::MatrixXd& fovis::MotionEstimator::getMotionEstimateCov ( ) const [inline]

Definition at line 61 of file motion_estimation.hpp.

Definition at line 53 of file motion_estimation.hpp.

int fovis::MotionEstimator::getNumInliers ( ) const [inline]

Definition at line 73 of file motion_estimation.hpp.

int fovis::MotionEstimator::getNumMatches ( ) const [inline]

Definition at line 69 of file motion_estimation.hpp.

Definition at line 77 of file motion_estimation.hpp.

Definition at line 49 of file motion_estimation.hpp.

void fovis::MotionEstimator::matchFeatures ( PyramidLevel ref_level,
PyramidLevel target_level 
) [private]

Definition at line 252 of file motion_estimation.cpp.

Definition at line 559 of file motion_estimation.cpp.

Definition at line 228 of file motion_estimation.cpp.


Member Data Documentation

Definition at line 141 of file motion_estimation.hpp.

Definition at line 95 of file motion_estimation.hpp.

Definition at line 161 of file motion_estimation.hpp.

Definition at line 137 of file motion_estimation.hpp.

Definition at line 97 of file motion_estimation.hpp.

Definition at line 100 of file motion_estimation.hpp.

Definition at line 102 of file motion_estimation.hpp.

Definition at line 151 of file motion_estimation.hpp.

Definition at line 133 of file motion_estimation.hpp.

Definition at line 114 of file motion_estimation.hpp.

Definition at line 145 of file motion_estimation.hpp.

Eigen::Isometry3d* fovis::MotionEstimator::_motion_estimate [private]

Definition at line 127 of file motion_estimation.hpp.

Definition at line 129 of file motion_estimation.hpp.

Definition at line 108 of file motion_estimation.hpp.

Definition at line 111 of file motion_estimation.hpp.

Definition at line 101 of file motion_estimation.hpp.

Definition at line 117 of file motion_estimation.hpp.

Definition at line 105 of file motion_estimation.hpp.

Definition at line 119 of file motion_estimation.hpp.

Definition at line 121 of file motion_estimation.hpp.

Definition at line 122 of file motion_estimation.hpp.

Definition at line 159 of file motion_estimation.hpp.

Definition at line 154 of file motion_estimation.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