Static Public Member Functions
haloc::Utils Class Reference

#include <utils.h>

List of all members.

Static Public Member Functions

static tf::Transform buildTransformation (Mat rvec, Mat tvec)
 compose the transformation matrix using 2 Mat as inputs: one for rotation and one for translation
static bool calculate3DPoint (const image_geometry::StereoCameraModel stereo_camera_model, const Point2d &left_point, const Point2d &right_point, double max_proj_err, Point3d &world_point)
 Compute the 3D point projecting the disparity.
static void crossCheckFilter (const vector< DMatch > &matches1to2, const vector< DMatch > &matches2to1, vector< DMatch > &checked_matches)
 filter matches of cross check matching
static void crossCheckThresholdMatching (const Mat &descriptors1, const Mat &descriptors2, double threshold, const Mat &match_mask, vector< DMatch > &matches)
 match descriptors of 2 images by threshold
static void descriptorExtraction (const Mat &image, vector< KeyPoint > &key_points, Mat &descriptors, string type)
 extract descriptors of some image
static void keypointDetector (const Mat &image, vector< KeyPoint > &key_points, string type)
 extract the keypoints of some image
static void ratioMatching (const Mat &descriptors1, const Mat &descriptors2, double ratio, const Mat &match_mask, vector< DMatch > &matches)
 match descriptors of 2 images by ratio
static bool sortByLikelihood (const pair< int, float > p1, const pair< int, float > p2)
 Sort 2 matchings by likelihood.
static bool sortByMatching (const pair< int, float > d1, const pair< int, float > d2)
 Sort 2 matchings by value.
static bool sortByResponse (const KeyPoint kp1, const KeyPoint kp2)
 Sort 2 keypoints by its response.
static bool sortDescByDistance (const DMatch &d1, const DMatch &d2)
 Sort 2 descriptors matchings by distance.
static void thresholdMatching (const Mat &descriptors1, const Mat &descriptors2, double threshold, const Mat &match_mask, vector< DMatch > &matches)
 match descriptors of 2 images by threshold

Detailed Description

Definition at line 17 of file utils.h.


Member Function Documentation

static tf::Transform haloc::Utils::buildTransformation ( Mat  rvec,
Mat  tvec 
) [inline, static]

compose the transformation matrix using 2 Mat as inputs: one for rotation and one for translation

Returns:
the transformation matrix
Parameters:
rveccv matrix with the rotation angles
tveccv matrix with the transformation x y z

Definition at line 323 of file utils.h.

static bool haloc::Utils::calculate3DPoint ( const image_geometry::StereoCameraModel  stereo_camera_model,
const Point2d &  left_point,
const Point2d &  right_point,
double  max_proj_err,
Point3d &  world_point 
) [inline, static]

Compute the 3D point projecting the disparity.

Returns:
Parameters:
stereo_camera_modelis the camera model
left_pointon the left image
right_pointon the right image
world_pointpointer to the corresponding 3d point

Definition at line 216 of file utils.h.

static void haloc::Utils::crossCheckFilter ( const vector< DMatch > &  matches1to2,
const vector< DMatch > &  matches2to1,
vector< DMatch > &  checked_matches 
) [inline, static]

filter matches of cross check matching

Returns:
Parameters:
matches1to2matches from image 1 to 2
matches2to1matches from image 2 to 1
matchesoutput vector with filtered matches

Definition at line 163 of file utils.h.

static void haloc::Utils::crossCheckThresholdMatching ( const Mat &  descriptors1,
const Mat &  descriptors2,
double  threshold,
const Mat &  match_mask,
vector< DMatch > &  matches 
) [inline, static]

match descriptors of 2 images by threshold

Returns:
Parameters:
descriptors1descriptors of image 1
descriptors2descriptors of image 2
thresholdto determine correct matchings
match_maskmask for matchings
matchesoutput vector with the matches

Definition at line 194 of file utils.h.

static void haloc::Utils::descriptorExtraction ( const Mat &  image,
vector< KeyPoint > &  key_points,
Mat &  descriptors,
string  type 
) [inline, static]

extract descriptors of some image

Returns:
Parameters:
imagethe source image
key_pointskeypoints of the source image
descriptorsis the pointer for the resulting image descriptors

Definition at line 59 of file utils.h.

static void haloc::Utils::keypointDetector ( const Mat &  image,
vector< KeyPoint > &  key_points,
string  type 
) [inline, static]

extract the keypoints of some image

Returns:
Parameters:
imagethe source image
key_pointsis the pointer for the resulting image key_points
typedescriptor type (see opencv docs)

Definition at line 28 of file utils.h.

static void haloc::Utils::ratioMatching ( const Mat &  descriptors1,
const Mat &  descriptors2,
double  ratio,
const Mat &  match_mask,
vector< DMatch > &  matches 
) [inline, static]

match descriptors of 2 images by ratio

Returns:
Parameters:
descriptors1descriptors of image1
descriptors2descriptors of image2
ratioto determine correct matchings
matchesoutput vector with the matches

Definition at line 81 of file utils.h.

static bool haloc::Utils::sortByLikelihood ( const pair< int, float >  p1,
const pair< int, float >  p2 
) [inline, static]

Sort 2 matchings by likelihood.

Returns:
true if likelihood 1 is greater than likelihood 2
Parameters:
likelihood1
likelihood2

Definition at line 312 of file utils.h.

static bool haloc::Utils::sortByMatching ( const pair< int, float >  d1,
const pair< int, float >  d2 
) [inline, static]

Sort 2 matchings by value.

Returns:
true if matching 1 is smaller than matching 2
Parameters:
matching1
matching2

Definition at line 282 of file utils.h.

static bool haloc::Utils::sortByResponse ( const KeyPoint  kp1,
const KeyPoint  kp2 
) [inline, static]

Sort 2 keypoints by its response.

Returns:
true if response of kp 1 is greater than response of kp 2
Parameters:
likelihood1
likelihood2

Definition at line 302 of file utils.h.

static bool haloc::Utils::sortDescByDistance ( const DMatch &  d1,
const DMatch &  d2 
) [inline, static]

Sort 2 descriptors matchings by distance.

Returns:
true if vector 1 is smaller than vector 2
Parameters:
descriptormatching 1
descriptormatching 2

Definition at line 292 of file utils.h.

static void haloc::Utils::thresholdMatching ( const Mat &  descriptors1,
const Mat &  descriptors2,
double  threshold,
const Mat &  match_mask,
vector< DMatch > &  matches 
) [inline, static]

match descriptors of 2 images by threshold

Returns:
Parameters:
descriptors1descriptors of image1
descriptors2descriptors of image2
thresholdto determine correct matchings
match_maskmask for matchings
matchesoutput vector with the matches

Definition at line 121 of file utils.h.


The documentation for this class was generated from the following file:


libhaloc
Author(s): Pep Lluis Negre
autogenerated on Thu Jun 6 2019 21:25:00