Main visual odometry class. More...
#include <visual_odometry.hpp>
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.
fovis::VisualOdometry::VisualOdometry | ( | const Rectification * | rectification, |
const VisualOdometryOptions & | options | ||
) |
Constructs a new visual odometry estimator.
rectification | specifies the input image dimensions, as well as the mapping from input image coordinates to rectified image coordinates. |
options | controls 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.
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.
bool fovis::VisualOdometry::getChangeReferenceFrames | ( | ) | const [inline] |
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.
Definition at line 297 of file visual_odometry.cpp.
int fovis::VisualOdometry::getFastThreshold | ( | ) | const [inline] |
Definition at line 166 of file visual_odometry.hpp.
const Eigen::Matrix3d& fovis::VisualOdometry::getInitialHomography | ( | ) | const [inline] |
Definition at line 173 of file visual_odometry.hpp.
const Eigen::Isometry3d& fovis::VisualOdometry::getMotionEstimate | ( | ) | const [inline] |
Definition at line 144 of file visual_odometry.hpp.
const Eigen::MatrixXd& fovis::VisualOdometry::getMotionEstimateCov | ( | ) | const [inline] |
Definition at line 152 of file visual_odometry.hpp.
MotionEstimateStatusCode fovis::VisualOdometry::getMotionEstimateStatus | ( | ) | const [inline] |
Definition at line 136 of file visual_odometry.hpp.
const MotionEstimator* fovis::VisualOdometry::getMotionEstimator | ( | ) | const [inline] |
Definition at line 159 of file visual_odometry.hpp.
const VisualOdometryOptions& fovis::VisualOdometry::getOptions | ( | ) | const [inline] |
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.
const OdometryFrame* fovis::VisualOdometry::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.
Definition at line 113 of file visual_odometry.hpp.
const OdometryFrame* fovis::VisualOdometry::getTargetFrame | ( | ) | const [inline] |
Retrieve the current target frame used for motion estimation.
Definition at line 120 of file visual_odometry.hpp.
void fovis::VisualOdometry::prepareFrame | ( | OdometryFrame * | frame | ) | [private] |
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.
gray | a 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_source | a 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.
void fovis::VisualOdometry::sanityCheck | ( | ) | const |
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.
bool fovis::VisualOdometry::_change_reference_frames [private] |
Definition at line 215 of file visual_odometry.hpp.
OdometryFrame* fovis::VisualOdometry::_cur_frame [private] |
Definition at line 209 of file visual_odometry.hpp.
MotionEstimator* fovis::VisualOdometry::_estimator [private] |
Definition at line 211 of file visual_odometry.hpp.
int fovis::VisualOdometry::_fast_threshold [private] |
Definition at line 226 of file visual_odometry.hpp.
float fovis::VisualOdometry::_fast_threshold_adaptive_gain [private] |
Definition at line 232 of file visual_odometry.hpp.
int fovis::VisualOdometry::_fast_threshold_max [private] |
Definition at line 230 of file visual_odometry.hpp.
int fovis::VisualOdometry::_fast_threshold_min [private] |
Definition at line 229 of file visual_odometry.hpp.
int fovis::VisualOdometry::_feature_window_size [private] |
Definition at line 221 of file visual_odometry.hpp.
long fovis::VisualOdometry::_frame_count [private] |
Definition at line 217 of file visual_odometry.hpp.
int fovis::VisualOdometry::_initial_rotation_pyramid_level [private] |
Definition at line 242 of file visual_odometry.hpp.
int fovis::VisualOdometry::_num_pyramid_levels [private] |
Definition at line 223 of file visual_odometry.hpp.
Definition at line 244 of file visual_odometry.hpp.
VisualOdometryPriv* fovis::VisualOdometry::_p [private] |
Definition at line 213 of file visual_odometry.hpp.
OdometryFrame* fovis::VisualOdometry::_prev_frame [private] |
Definition at line 208 of file visual_odometry.hpp.
const Rectification* fovis::VisualOdometry::_rectification [private] |
Definition at line 205 of file visual_odometry.hpp.
OdometryFrame* fovis::VisualOdometry::_ref_frame [private] |
Definition at line 207 of file visual_odometry.hpp.
int fovis::VisualOdometry::_ref_frame_change_threshold [private] |
Definition at line 239 of file visual_odometry.hpp.
int fovis::VisualOdometry::_target_pixels_per_feature [private] |
Definition at line 231 of file visual_odometry.hpp.
bool fovis::VisualOdometry::_use_adaptive_threshold [private] |
Definition at line 234 of file visual_odometry.hpp.
bool fovis::VisualOdometry::_use_homography_initialization [private] |
Definition at line 235 of file visual_odometry.hpp.