Does the heavy lifting for frame-to-frame motion estimation. More...
#include <motion_estimation.hpp>
Does the heavy lifting for frame-to-frame motion estimation.
TODO
Definition at line 37 of file motion_estimation.hpp.
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.
void fovis::MotionEstimator::computeMaximallyConsistentClique | ( | ) | [private] |
Definition at line 390 of file motion_estimation.cpp.
void fovis::MotionEstimator::computeReprojectionError | ( | ) | [private] |
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.
void fovis::MotionEstimator::estimateRigidBodyTransform | ( | ) | [private] |
Definition at line 520 of file motion_estimation.cpp.
const FeatureMatch* fovis::MotionEstimator::getMatches | ( | ) | const [inline] |
Definition at line 65 of file motion_estimation.hpp.
double fovis::MotionEstimator::getMeanInlierReprojectionError | ( | ) | const [inline] |
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.
MotionEstimateStatusCode fovis::MotionEstimator::getMotionEstimateStatus | ( | ) | const [inline] |
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.
int fovis::MotionEstimator::getNumReprojectionFailures | ( | ) | const [inline] |
Definition at line 77 of file motion_estimation.hpp.
bool fovis::MotionEstimator::isMotionEstimateValid | ( | ) | const [inline] |
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.
void fovis::MotionEstimator::refineMotionEstimate | ( | ) | [private] |
Definition at line 559 of file motion_estimation.cpp.
void fovis::MotionEstimator::sanityCheck | ( | ) | const |
Definition at line 228 of file motion_estimation.cpp.
double fovis::MotionEstimator::_clique_inlier_threshold [private] |
Definition at line 141 of file motion_estimation.hpp.
DepthSource* fovis::MotionEstimator::_depth_source [private] |
Definition at line 95 of file motion_estimation.hpp.
Definition at line 161 of file motion_estimation.hpp.
double fovis::MotionEstimator::_inlier_max_reprojection_error [private] |
Definition at line 137 of file motion_estimation.hpp.
Definition at line 97 of file motion_estimation.hpp.
FeatureMatch* fovis::MotionEstimator::_matches [private] |
Definition at line 100 of file motion_estimation.hpp.
int fovis::MotionEstimator::_matches_capacity [private] |
Definition at line 102 of file motion_estimation.hpp.
double fovis::MotionEstimator::_max_feature_motion [private] |
Definition at line 151 of file motion_estimation.hpp.
double fovis::MotionEstimator::_max_mean_reprojection_error [private] |
Definition at line 133 of file motion_estimation.hpp.
double fovis::MotionEstimator::_mean_reprojection_error [private] |
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.
Eigen::MatrixXd* fovis::MotionEstimator::_motion_estimate_covariance [private] |
Definition at line 129 of file motion_estimation.hpp.
int fovis::MotionEstimator::_num_frames [private] |
Definition at line 108 of file motion_estimation.hpp.
int fovis::MotionEstimator::_num_inliers [private] |
Definition at line 111 of file motion_estimation.hpp.
int fovis::MotionEstimator::_num_matches [private] |
Definition at line 101 of file motion_estimation.hpp.
int fovis::MotionEstimator::_num_reprojection_failures [private] |
Definition at line 117 of file motion_estimation.hpp.
int fovis::MotionEstimator::_num_tracks [private] |
Definition at line 105 of file motion_estimation.hpp.
const Rectification* fovis::MotionEstimator::_rectification [private] |
Definition at line 119 of file motion_estimation.hpp.
OdometryFrame* fovis::MotionEstimator::_ref_frame [private] |
Definition at line 121 of file motion_estimation.hpp.
Definition at line 122 of file motion_estimation.hpp.
bool fovis::MotionEstimator::_update_target_features_with_refined [private] |
Definition at line 159 of file motion_estimation.hpp.
int fovis::MotionEstimator::_use_subpixel_refinement [private] |
Definition at line 154 of file motion_estimation.hpp.