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... | |
struct | Point |
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, tictoc_t > | TictocMap |
typedef std::map< std::string, std::string > | VisualOdometryOptions |
Options. | |
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 void | _initializeTictoc () |
static Eigen::Vector3d | _quat_to_roll_pitch_yaw (const Eigen::Quaterniond &q) |
static Eigen::Quaterniond | _rpy_to_quat (const Eigen::Vector3d rpy) |
static bool | _tictoc_t_alphCompare (const tictoc_t *t1, const tictoc_t *t2) |
static bool | _tictoc_t_avgTimeCompare (const tictoc_t *t1, const tictoc_t *t2) |
static bool | _tictoc_t_emaTimeCompare (const tictoc_t *t1, const tictoc_t *t2) |
static bool | _tictoc_t_maxTimeCompare (const tictoc_t *t1, const tictoc_t *t2) |
static bool | _tictoc_t_minTimeCompare (const tictoc_t *t1, const tictoc_t *t2) |
static bool | _tictoc_t_totalTimeCompare (const tictoc_t *t1, const tictoc_t *t2) |
static int64_t | _timestamp_now () |
static std::string | _toString (double v) |
static int | clamp (int val, int minval, int maxval) |
static void | computeProjectionJacobian (const Eigen::Matrix< double, 6, 1 > ¶ms, double fx, double px, double py, const Eigen::Matrix< double, 4, Eigen::Dynamic > &points, Eigen::Matrix< double, Eigen::Dynamic, 6 > *result, int result_row_offset) |
static void | computeReprojectionError (const Eigen::Matrix< double, 4, Eigen::Dynamic > &points, const Eigen::Matrix< double, 2, Eigen::Dynamic > &ref_projections, const Eigen::Matrix< double, 3, 4 > &K, const Eigen::Isometry3d &motion, Eigen::VectorXd *err, int err_offset) |
static void | computeReverseProjectionJacobian (const Eigen::Matrix< double, 6, 1 > ¶ms, double fx, double px, double py, const Eigen::Matrix< double, 4, Eigen::Dynamic > &points, Eigen::Matrix< double, Eigen::Dynamic, 6 > *result, int result_row_offset) |
static bool | consistencyCompare (const FeatureMatch &ca, const FeatureMatch &cb) |
static int | dot_int16_aligned (const int16_t *a, const int16_t *b, int num_taps) |
void | FAST (const uint8_t *img, int width, int height, int row_stride, std::vector< KeyPoint > *keypoints, int threshold, bool nonmax_suppression) |
void | FAST (const uint8_t *image, int width, int height, int row_stride, vector< KeyPoint > *keypoints, int threshold, bool nonmax_suppression) |
static void | fast9ComputeScores (const uint8_t *img, int width, int height, int row_stride, vector< Point > &corners, vector< int > &scores, int b) |
static int | fast9CornerScore (const unsigned char *p, const int pixel[], int bstart) |
static void | fast9Detect (const uint8_t *img, int width, int height, int row_stride, vector< Point > &ret_corners, int b) |
static void | fastNonmaxSuppression (const vector< Point > &corners, const vector< int > &scores, vector< KeyPoint > &ret_nonmax) |
static void | grayToEigen (const uint8_t *grayData, int width, int height, int stride, int downsampleFactor, Eigen::MatrixXf *result) |
static Eigen::Isometry3d | isometryFromParams (const Eigen::Matrix< double, 6, 1 > ¶ms) |
static Eigen::Matrix< double, 6, 1 > | isometryToParams (const Eigen::Isometry3d &M) |
static bool | keypoint_rect_v_comparator (const KeypointData &a, const KeypointData &b) |
static bool | keypoint_score_comparator (const KeyPoint &a, const KeyPoint &b) |
static void | makeOffsets (int pixel[], int row_stride) |
static void | mean_stddev (const uint8_t *buf, int stride, int width, int height, float *mean, float *stddev) |
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 px, double py, 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 px, double py, const Eigen::Isometry3d &initial_estimate, int max_iterations, Eigen::Isometry3d *result, Eigen::MatrixXd *result_covariance) |
static bool | robustStereoCompatibility (const Eigen::Vector3d &C1, const Eigen::Vector3d &C2, const Eigen::Vector3d &P1, const Eigen::Vector3d &P2, double baseline, double focal_length, double De) |
static double | robustStereoCompatibility_computeDL (double L, const Eigen::Vector3d &p1, const Eigen::Vector3d &p2, double t, double f, double De) |
static int | round_up_to_multiple (int x, int a) |
static double | sqr (double x) |
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) |
static void | validateOptions (const VisualOdometryOptions &options, const VisualOdometryOptions &defaults) |
Variables | |
static int | _tictoc_enabled = 1 |
static int | _tictoc_initialized = 0 |
static TictocMap | _tictoc_map |
const char * | MotionEstimateStatusCodeStrings [] |
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
typedef std::map<std::string, tictoc_t> fovis::TictocMap |
Definition at line 97 of file tictoc.cpp.
Status of a feature match.
MATCH_NEEDS_DEPTH_REFINEMENT |
match is ok, but needs depth refinement. |
MATCH_REFINEMENT_FAILED |
match should be rejected. |
MATCH_OK |
match is ok. |
Definition at line 19 of file feature_match.hpp.
Definition at line 20 of file motion_estimation.hpp.
tictoc_sort_type_t:
Different Options for sorting the printed results
Definition at line 71 of file tictoc.hpp.
static void fovis::_initializeTictoc | ( | ) | [static] |
Definition at line 101 of file tictoc.cpp.
static Eigen::Vector3d fovis::_quat_to_roll_pitch_yaw | ( | const Eigen::Quaterniond & | q | ) | [inline, static] |
Definition at line 27 of file internal_utils.hpp.
static Eigen::Quaterniond fovis::_rpy_to_quat | ( | const Eigen::Vector3d | rpy | ) | [inline, static] |
Definition at line 43 of file internal_utils.hpp.
static bool fovis::_tictoc_t_alphCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 85 of file tictoc.cpp.
static bool fovis::_tictoc_t_avgTimeCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 34 of file tictoc.cpp.
static bool fovis::_tictoc_t_emaTimeCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 74 of file tictoc.cpp.
static bool fovis::_tictoc_t_maxTimeCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 54 of file tictoc.cpp.
static bool fovis::_tictoc_t_minTimeCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 64 of file tictoc.cpp.
static bool fovis::_tictoc_t_totalTimeCompare | ( | const tictoc_t * | t1, |
const tictoc_t * | t2 | ||
) | [static] |
Definition at line 44 of file tictoc.cpp.
static int64_t fovis::_timestamp_now | ( | ) | [static] |
Definition at line 26 of file tictoc.cpp.
static std::string fovis::_toString | ( | double | v | ) | [static] |
Definition at line 289 of file visual_odometry.cpp.
static int fovis::clamp | ( | int | val, |
int | minval, | ||
int | maxval | ||
) | [inline, static] |
Definition at line 45 of file visual_odometry.cpp.
static void fovis::computeProjectionJacobian | ( | const Eigen::Matrix< double, 6, 1 > & | params, |
double | fx, | ||
double | px, | ||
double | py, | ||
const Eigen::Matrix< double, 4, Eigen::Dynamic > & | points, | ||
Eigen::Matrix< double, Eigen::Dynamic, 6 > * | result, | ||
int | result_row_offset | ||
) | [static] |
Definition at line 90 of file refine_motion_estimate.cpp.
static void fovis::computeReprojectionError | ( | const Eigen::Matrix< double, 4, Eigen::Dynamic > & | points, |
const Eigen::Matrix< double, 2, Eigen::Dynamic > & | ref_projections, | ||
const Eigen::Matrix< double, 3, 4 > & | K, | ||
const Eigen::Isometry3d & | motion, | ||
Eigen::VectorXd * | err, | ||
int | err_offset | ||
) | [static] |
Definition at line 66 of file refine_motion_estimate.cpp.
static void fovis::computeReverseProjectionJacobian | ( | const Eigen::Matrix< double, 6, 1 > & | params, |
double | fx, | ||
double | px, | ||
double | py, | ||
const Eigen::Matrix< double, 4, Eigen::Dynamic > & | points, | ||
Eigen::Matrix< double, Eigen::Dynamic, 6 > * | result, | ||
int | result_row_offset | ||
) | [static] |
Definition at line 251 of file refine_motion_estimate.cpp.
static bool fovis::consistencyCompare | ( | const FeatureMatch & | ca, |
const FeatureMatch & | cb | ||
) | [static] |
Definition at line 342 of file motion_estimation.cpp.
static int fovis::dot_int16_aligned | ( | const int16_t * | a, |
const int16_t * | b, | ||
int | num_taps | ||
) | [inline, static] |
Definition at line 13 of file refine_feature_match.cpp.
void fovis::FAST | ( | const uint8_t * | img, |
int | width, | ||
int | height, | ||
int | row_stride, | ||
std::vector< KeyPoint > * | keypoints, | ||
int | threshold, | ||
bool | nonmax_suppression | ||
) |
void fovis::FAST | ( | const uint8_t * | image, |
int | width, | ||
int | height, | ||
int | row_stride, | ||
vector< KeyPoint > * | keypoints, | ||
int | threshold, | ||
bool | nonmax_suppression | ||
) |
static void fovis::fast9ComputeScores | ( | const uint8_t * | img, |
int | width, | ||
int | height, | ||
int | row_stride, | ||
vector< Point > & | corners, | ||
vector< int > & | scores, | ||
int | b | ||
) | [static] |
static int fovis::fast9CornerScore | ( | const unsigned char * | p, |
const int | pixel[], | ||
int | bstart | ||
) | [static] |
static void fovis::fast9Detect | ( | const uint8_t * | img, |
int | width, | ||
int | height, | ||
int | row_stride, | ||
vector< Point > & | ret_corners, | ||
int | b | ||
) | [static] |
static void fovis::fastNonmaxSuppression | ( | const vector< Point > & | corners, |
const vector< int > & | scores, | ||
vector< KeyPoint > & | ret_nonmax | ||
) | [static] |
static void fovis::grayToEigen | ( | const uint8_t * | grayData, |
int | width, | ||
int | height, | ||
int | stride, | ||
int | downsampleFactor, | ||
Eigen::MatrixXf * | result | ||
) | [static] |
Definition at line 24 of file initial_homography_estimation.cpp.
static Eigen::Isometry3d fovis::isometryFromParams | ( | const Eigen::Matrix< double, 6, 1 > & | params | ) | [inline, static] |
Definition at line 19 of file refine_motion_estimate.cpp.
static Eigen::Matrix<double, 6, 1> fovis::isometryToParams | ( | const Eigen::Isometry3d & | M | ) | [inline, static] |
Definition at line 48 of file refine_motion_estimate.cpp.
static bool fovis::keypoint_rect_v_comparator | ( | const KeypointData & | a, |
const KeypointData & | b | ||
) | [static] |
Definition at line 23 of file stereo_frame.cpp.
static bool fovis::keypoint_score_comparator | ( | const KeyPoint & | a, |
const KeyPoint & | b | ||
) | [static] |
Definition at line 14 of file grid_filter.cpp.
static void fovis::makeOffsets | ( | int | pixel[], |
int | row_stride | ||
) | [inline, static] |
static void fovis::mean_stddev | ( | const uint8_t * | buf, |
int | stride, | ||
int | width, | ||
int | height, | ||
float * | mean, | ||
float * | stddev | ||
) | [static] |
Definition at line 10 of file normalize_image.cpp.
void fovis::normalize_image | ( | uint8_t * | buf, |
int | stride, | ||
int | width, | ||
int | height | ||
) |
Normalize image intensities in place to approximately have mean 128 and sd 74.
Definition at line 29 of file normalize_image.cpp.
bool fovis::optionsGetBool | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
bool * | result | ||
) |
Definition at line 31 of file internal_utils.cpp.
bool fovis::optionsGetBoolOrFromDefault | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
const VisualOdometryOptions & | defaults | ||
) |
Definition at line 73 of file internal_utils.cpp.
bool fovis::optionsGetDouble | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
double * | result | ||
) |
Definition at line 88 of file internal_utils.cpp.
double fovis::optionsGetDoubleOrFromDefault | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
const VisualOdometryOptions & | defaults | ||
) |
Definition at line 109 of file internal_utils.cpp.
bool fovis::optionsGetInt | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
int * | result | ||
) |
Definition at line 10 of file internal_utils.cpp.
int fovis::optionsGetIntOrFromDefault | ( | const VisualOdometryOptions & | options, |
std::string | name, | ||
const VisualOdometryOptions & | defaults | ||
) |
Definition at line 58 of file internal_utils.cpp.
static void fovis::print_isometry | ( | const Eigen::Isometry3d & | iso | ) | [inline, static] |
Definition at line 68 of file internal_utils.hpp.
void fovis::refineFeatureMatch | ( | PyramidLevel * | ref_level, |
PyramidLevel * | target_level, | ||
Eigen::Vector2d | ref_uv, | ||
Eigen::Vector2d | init_target_uv, | ||
Eigen::Vector2d * | final_target_uv, | ||
float * | delta_sse | ||
) |
Definition at line 80 of file refine_feature_match.cpp.
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.
Definition at line 161 of file refine_motion_estimate.cpp.
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.
Definition at line 333 of file refine_motion_estimate.cpp.
static bool fovis::robustStereoCompatibility | ( | const Eigen::Vector3d & | C1, |
const Eigen::Vector3d & | C2, | ||
const Eigen::Vector3d & | P1, | ||
const Eigen::Vector3d & | P2, | ||
double | baseline, | ||
double | focal_length, | ||
double | De | ||
) | [inline, static] |
Definition at line 372 of file motion_estimation.cpp.
static double fovis::robustStereoCompatibility_computeDL | ( | double | L, |
const Eigen::Vector3d & | p1, | ||
const Eigen::Vector3d & | p2, | ||
double | t, | ||
double | f, | ||
double | De | ||
) | [inline, static] |
Definition at line 357 of file motion_estimation.cpp.
static int fovis::round_up_to_multiple | ( | int | x, |
int | a | ||
) | [inline, static] |
Definition at line 18 of file internal_utils.hpp.
static double fovis::sqr | ( | double | x | ) | [inline, static] |
Definition at line 354 of file motion_estimation.cpp.
void fovis::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 | ||
) |
Definition at line 9 of file stereo_rectify.cpp.
int64_t fovis::tictoc | ( | const char * | description | ) |
tictoc:
basic invocation, the second time its called, it returns the time difference in microseconds
Definition at line 113 of file tictoc.cpp.
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
Definition at line 119 of file tictoc.cpp.
void fovis::tictoc_get_stats | ( | std::vector< tictoc_t > * | stats | ) |
Get tictoc entries.
Definition at line 172 of file tictoc.cpp.
void fovis::tictoc_print_stats | ( | tictoc_sort_type_t | sortType | ) |
static void fovis::validateOptions | ( | const VisualOdometryOptions & | options, |
const VisualOdometryOptions & | defaults | ||
) | [static] |
Definition at line 339 of file visual_odometry.cpp.
int fovis::_tictoc_enabled = 1 [static] |
Definition at line 95 of file tictoc.cpp.
int fovis::_tictoc_initialized = 0 [static] |
Definition at line 96 of file tictoc.cpp.
TictocMap fovis::_tictoc_map [static] |
Definition at line 98 of file tictoc.cpp.
const char * fovis::MotionEstimateStatusCodeStrings |
{ "NO_DATA", "SUCCESS", "INSUFFICIENT_INLIERS", "OPTIMIZATION_FAILURE", "REPROJECTION_ERROR" }
Definition at line 31 of file motion_estimation.cpp.