libfovis
|
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 MotionEstimator * | getMotionEstimator () const |
const VisualOdometryOptions & | getOptions () const |
const Eigen::Isometry3d & | getPose () |
const OdometryFrame * | getReferenceFrame () const |
const OdometryFrame * | getTargetFrame () 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 () |
Main visual odometry class.
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.
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. |
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.
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. |
|
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.
|
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.
|
inline |
Retrieve the current target frame used for motion estimation.
|
inline |
If this returns true, then the current target frame will become the reference frame on the next call to processFrame().
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
static |
void sanityCheck | ( | ) | const |
Performs some internal sanity checks and aborts the program on failure. This is for debugging only.