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

Estimates a rough 2D homography registering two images. More...

#include <initial_homography_estimation.hpp>

List of all members.

Public Member Functions

void setTemplateImage (const uint8_t *grayData, int width, int height, int stride, int downsampleFactor)
void setTestImage (const uint8_t *grayData, int width, int height, int stride, int downsampleFactor)
Eigen::Matrix3f track (const Eigen::Matrix3f &init_H, int nIters, double *finalRMS)

Private Member Functions

Eigen::MatrixXf computeJacobian (const Eigen::ArrayXf &dx, const Eigen::ArrayXf &dy) const
Eigen::MatrixXf constructWarpedImage (const Eigen::MatrixXf &srcImage, const Eigen::MatrixXf &warpedPoints) const
Eigen::Matrix3f lieToH (const Eigen::VectorXf &lie) const

Static Private Member Functions

static double computeError (const Eigen::MatrixXf &error)
static void computeGradient (const Eigen::MatrixXf &image, Eigen::MatrixXf *dxp, Eigen::MatrixXf *dyp)
static Eigen::ArrayXf flattenMatrix (Eigen::MatrixXf &m)

Private Attributes

Eigen::MatrixXf errorIm
int template_cols
int template_rows
Eigen::ArrayXf templateDxRow
Eigen::ArrayXf templateDyRow
Eigen::MatrixXf templateImage
Eigen::MatrixXf templatePoints
Eigen::MatrixXf testImage
Eigen::MatrixXf warpedTestImage
Eigen::ArrayXf xx
Eigen::ArrayXf yy

Detailed Description

Estimates a rough 2D homography registering two images.

Definition at line 14 of file initial_homography_estimation.hpp.


Member Function Documentation

double fovis::InitialHomographyEstimator::computeError ( const Eigen::MatrixXf &  error) [static, private]

Compute the error (RMS) for the passed in difference image

Definition at line 93 of file initial_homography_estimation.cpp.

void fovis::InitialHomographyEstimator::computeGradient ( const Eigen::MatrixXf &  image,
Eigen::MatrixXf *  dxp,
Eigen::MatrixXf *  dyp 
) [static, private]

Compute the x/y gradient of the passed in image

Definition at line 174 of file initial_homography_estimation.cpp.

Eigen::MatrixXf fovis::InitialHomographyEstimator::computeJacobian ( const Eigen::ArrayXf &  dx,
const Eigen::ArrayXf &  dy 
) const [private]

form the Jacobian

Definition at line 199 of file initial_homography_estimation.cpp.

Eigen::MatrixXf fovis::InitialHomographyEstimator::constructWarpedImage ( const Eigen::MatrixXf &  srcImage,
const Eigen::MatrixXf &  warpedPoints 
) const [private]

Warp srcImage according to the warped points

Definition at line 218 of file initial_homography_estimation.cpp.

Eigen::ArrayXf fovis::InitialHomographyEstimator::flattenMatrix ( Eigen::MatrixXf &  m) [static, private]

Flatten an image stored as a matrix down into a row vector

Definition at line 18 of file initial_homography_estimation.cpp.

Eigen::Matrix3f fovis::InitialHomographyEstimator::lieToH ( const Eigen::VectorXf &  lie) const [private]

Compute the homography from the lie parameterization

Definition at line 208 of file initial_homography_estimation.cpp.

void fovis::InitialHomographyEstimator::setTemplateImage ( const uint8_t *  grayData,
int  width,
int  height,
int  stride,
int  downsampleFactor 
)

Set the template image to the passed in arguments. assumes the image data is row-major. The image will be downsampled by $ 1/2^{downsampleFactor} $

Definition at line 63 of file initial_homography_estimation.cpp.

void fovis::InitialHomographyEstimator::setTestImage ( const uint8_t *  grayData,
int  width,
int  height,
int  stride,
int  downsampleFactor 
)

Set the test image accordingly. The opimization will warp this image to match the template assumes the image data is row-major. The image will be downsampled by $ 1/2^{downsampleFactor} $

Definition at line 58 of file initial_homography_estimation.cpp.

Eigen::Matrix3f fovis::InitialHomographyEstimator::track ( const Eigen::Matrix3f &  init_H,
int  nIters,
double *  finalRMS 
)

Run ESM to find the homography between the template and test images. These should have already been passed in using the methods setTemplateImage(), and setTestImage().

Definition at line 98 of file initial_homography_estimation.cpp.


Member Data Documentation

Eigen::MatrixXf fovis::InitialHomographyEstimator::errorIm [private]

Definition at line 43 of file initial_homography_estimation.hpp.

Definition at line 40 of file initial_homography_estimation.hpp.

Definition at line 40 of file initial_homography_estimation.hpp.

Definition at line 44 of file initial_homography_estimation.hpp.

Definition at line 44 of file initial_homography_estimation.hpp.

Definition at line 41 of file initial_homography_estimation.hpp.

Definition at line 45 of file initial_homography_estimation.hpp.

Definition at line 41 of file initial_homography_estimation.hpp.

Definition at line 42 of file initial_homography_estimation.hpp.

Eigen::ArrayXf fovis::InitialHomographyEstimator::xx [private]

Definition at line 46 of file initial_homography_estimation.hpp.

Eigen::ArrayXf fovis::InitialHomographyEstimator::yy [private]

Definition at line 46 of file initial_homography_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