libfovis
Classes | Typedefs | Enumerations | Functions | Variables
fovis Namespace Reference

quick and dirty profiling tool.inspired by the matlab tic/toc command More...

Classes

struct  CameraIntrinsicsParameters
 Intrinsic parameters for a pinhole camera with plumb-bob distortion model. More...
 
class  DepthImage
 Depth source where a fully dense, metric depth image is available. More...
 
class  DepthSource
 Provides depth estimates for input image pixels. More...
 
class  FeatureMatch
 Represents a single image feature matched between two camera images taken at different times. More...
 
class  FeatureMatcher
 Matches features between a reference and a target image. More...
 
class  GridKeyPointFilter
 Places features into grid cells and discards the weakest features in each cell. More...
 
class  InitialHomographyEstimator
 Estimates a rough 2D homography registering two images. More...
 
class  IntensityDescriptorExtractor
 Extracts mean-normalized intensity patch around a pixel. More...
 
class  KeyPoint
 An interesting point in an image. More...
 
class  KeypointData
 Image feature used for motion estimation. More...
 
class  MotionEstimator
 Does the heavy lifting for frame-to-frame motion estimation. More...
 
class  OdometryFrame
 Stores data specific to an input frame. More...
 
class  PrimeSenseCalibration
 Computes useful information from a PrimeSenseCalibrationParameters object. More...
 
struct  PrimeSenseCalibrationParameters
 Calibration data structure for Kinect / PrimeSense sensors. More...
 
class  PrimeSenseDepth
 Stores depth data for a Kinect / PrimeSense camera. More...
 
class  PyramidLevel
 One level of a Gaussian image pyramid. More...
 
class  Rectification
 Maps image coordinates from an input image to image coordinates on a rectified camera. More...
 
class  SAD
 Calculates the Sum of Absolute Deviations (SAD) score between two vectors of length descriptor_len. More...
 
class  StereoCalibration
 Computes useful information from a StereoCalibrationParameters object. More...
 
struct  StereoCalibrationParameters
 Calibration data structure for stereo cameras. More...
 
class  StereoDepth
 Stores image data for a stereo camera pair. More...
 
class  StereoDisparity
 Depth source for a calibrated stereo camera pair where a dense disparity map has been precomputed. More...
 
class  StereoFrame
 Stores the right-hand image for a stereo pair. More...
 
struct  tictoc_t
 
class  VisualOdometry
 Main visual odometry class. More...
 
class  VisualOdometryPriv
 

Typedefs

typedef std::map< std::string, std::string > VisualOdometryOptions
 Options. More...
 

Enumerations

enum  MatchStatusCode { MATCH_NEEDS_DEPTH_REFINEMENT, MATCH_REFINEMENT_FAILED, MATCH_OK }
 
enum  MotionEstimateStatusCode {
  NO_DATA, SUCCESS, INSUFFICIENT_INLIERS, OPTIMIZATION_FAILURE,
  REPROJECTION_ERROR
}
 
enum  tictoc_sort_type_t {
  TICTOC_AVG, TICTOC_TOTAL, TICTOC_MIN, TICTOC_MAX,
  TICTOC_EMA, TICTOC_ALPHABETICAL
}
 

Functions

static Eigen::Vector3d _quat_to_roll_pitch_yaw (const Eigen::Quaterniond &q)
 
static Eigen::Quaterniond _rpy_to_quat (const Eigen::Vector3d rpy)
 
void FAST (const uint8_t *img, int width, int height, int row_stride, std::vector< KeyPoint > *keypoints, int threshold, bool nonmax_suppression)
 
void normalize_image (uint8_t *buf, int stride, int width, int height)
 Normalize image intensities in place to approximately have mean 128 and sd 74.
 
bool optionsGetBool (const VisualOdometryOptions &options, std::string name, bool *result)
 
bool optionsGetBoolOrFromDefault (const VisualOdometryOptions &options, std::string name, const VisualOdometryOptions &defaults)
 
bool optionsGetDouble (const VisualOdometryOptions &options, std::string name, double *result)
 
double optionsGetDoubleOrFromDefault (const VisualOdometryOptions &options, std::string name, const VisualOdometryOptions &defaults)
 
bool optionsGetInt (const VisualOdometryOptions &options, std::string name, int *result)
 
int optionsGetIntOrFromDefault (const VisualOdometryOptions &options, std::string name, const VisualOdometryOptions &defaults)
 
static void print_isometry (const Eigen::Isometry3d &iso)
 
void refineFeatureMatch (PyramidLevel *ref_level, PyramidLevel *target_level, Eigen::Vector2d ref_uv, Eigen::Vector2d init_target_uv, Eigen::Vector2d *final_target_uv, float *delta_sse)
 
Eigen::Isometry3d refineMotionEstimate (const Eigen::Matrix< double, 4, Eigen::Dynamic > &points, const Eigen::Matrix< double, 2, Eigen::Dynamic > &ref_projections, double fx, double cx, double cy, const Eigen::Isometry3d &initial_estimate, int max_iterations)
 
void refineMotionEstimateBidirectional (const Eigen::Matrix< double, 4, Eigen::Dynamic > &ref_points, const Eigen::Matrix< double, 2, Eigen::Dynamic > &ref_projections, const Eigen::Matrix< double, 4, Eigen::Dynamic > &target_points, const Eigen::Matrix< double, 2, Eigen::Dynamic > &target_projections, double fx, double cx, double cy, const Eigen::Isometry3d &initial_estimate, int max_iterations, Eigen::Isometry3d *result, Eigen::MatrixXd *result_covariance)
 
static int round_up_to_multiple (int x, int a)
 
void stereo_rectify (const CameraIntrinsicsParameters &left_params, const CameraIntrinsicsParameters &right_params, const Eigen::Quaterniond &rotation_quat, const Eigen::Vector3d &translation, Eigen::Matrix3d *left_rotation, Eigen::Matrix3d *right_rotation, CameraIntrinsicsParameters *rectified_params)
 
int64_t tictoc (const char *description)
 
int64_t tictoc_full (const char *description, double ema_alpha, int64_t *ema)
 
void tictoc_get_stats (std::vector< tictoc_t > *stats)
 
void tictoc_print_stats (tictoc_sort_type_t sortType)
 

Variables

const char * MotionEstimateStatusCodeStrings []
 

Detailed Description

quick and dirty profiling tool.

inspired by the matlab tic/toc command

call tictoc("description") to set the timer going call it again with the same description to stop the timer

Note: To get output, set the "FOVIS_TICTOC" environment variable to something

Enumeration Type Documentation

Status of a feature match.

Enumerator
MATCH_NEEDS_DEPTH_REFINEMENT 

match is ok, but needs depth refinement.

MATCH_REFINEMENT_FAILED 

match should be rejected.

MATCH_OK 

match is ok.

tictoc_sort_type_t:

Different Options for sorting the printed results

Function Documentation

Eigen::Isometry3d fovis::refineMotionEstimate ( const Eigen::Matrix< double, 4, Eigen::Dynamic > &  points,
const Eigen::Matrix< double, 2, Eigen::Dynamic > &  ref_projections,
double  fx,
double  cx,
double  cy,
const Eigen::Isometry3d &  initial_estimate,
int  max_iterations 
)

Given an initial motion estimate M_0, iteratively refines the motion estimate to minimize reprojection error.

M = argmin_{M} {i} || ref_projections[i] - p(K * M * points[i]) ||^2

where K is the camera projection matrix formed by fx, cx, and cy:

K = [ fx 0 cx 0 0 fx cy 0 0 0 1 0 ]

and p(X) is the normalized form of a homogeneous coordinate.

void fovis::refineMotionEstimateBidirectional ( const Eigen::Matrix< double, 4, Eigen::Dynamic > &  ref_points,
const Eigen::Matrix< double, 2, Eigen::Dynamic > &  ref_projections,
const Eigen::Matrix< double, 4, Eigen::Dynamic > &  target_points,
const Eigen::Matrix< double, 2, Eigen::Dynamic > &  target_projections,
double  fx,
double  cx,
double  cy,
const Eigen::Isometry3d &  initial_estimate,
int  max_iterations,
Eigen::Isometry3d *  result,
Eigen::MatrixXd *  result_covariance 
)

Given an initial motion estimate M_0, iteratively refines the motion estimate to minimize bidirectional reprojection error.

M = argmin_{M} {i} ref_err(i) + target_err(i)

ref_err(i) = || ref_projections[i] - p(K * M * target_points[i]) ||^2 target_err(i) = || target_projections[i] - p(K * M * ref_points[i]) ||^2

where K is the camera projection matrix formed by fx, fy, cx, and cy:

K = [ fx 0 cx 0 0 fy cy 0 0 0 1 0 ]

and p(X) is the normalized form of a homogeneous coordinate.

int64_t fovis::tictoc ( const char *  description)

tictoc:

basic invocation, the second time its called, it returns the time difference in microseconds

int64_t fovis::tictoc_full ( const char *  description,
double  ema_alpha,
int64_t *  ema 
)

tictoc_full:

full invocation, allows you to specify an exponential moving average rate, and the current EMA value is returned in the ema argument

void fovis::tictoc_print_stats ( tictoc_sort_type_t  sortType)

tictoc_print_stats:

Print Out the stats from tictoc

void fovis::tictoc_get_stats ( std::vector< tictoc_t > *  stats)

Get tictoc entries.