MRPT logo

mrpt::vision Namespace Reference

Classes for computer vision, detectors, features, etc. More...


Classes

struct  TCamera
 AJOGD Estructura para almacenar los datos de la camara para MONOSLAM. More...
class  CCamModel
 This class represent the camera model for Monocular SLAM. More...
class  CFeature
 A generic 2D feature from an image. More...
class  CFeatureList
 A list of features. More...
class  CMatchedFeatureList
 A list of features. More...
class  CFeatureExtraction
class  CGaussianConvolutionKernel
 This class represents a generic "convolution kernel", that can actually represent any Gaussian or DOG filter. More...
class  CImageConvolution
 This class performs filtering on a image based on Gaussian or DOG filters. More...
struct  TCaptureOptions_dc1394
 Options used when creating an dc1394 capture object All but the frame size, framerate, and color_coding can be changed dynamically by CImageGrabber_dc1394::changeCaptureOptions. More...
class  CImageGrabber_dc1394
 A class for grabing images from a IEEE1394 (Firewire) camera using the libdc1394-2 library. More...
struct  TCaptureCVOptions
 Options used when creating an OpenCV capture object Some options apply to IEEE1394 cameras only. More...
class  CImageGrabber_OpenCV
 A class for grabing images from a "OpenCV"-compatible camera, or from an AVI video file. More...
class  CStereoGrabber_Bumblebee
 A class for grabing stereo images from a "Bumblebee" camera NOTE:
  • This class is only available when compiling MRPT with "#define MRPT_HAS_BUMBLEBEE 1" in the "config.h".
More...
class  CStereoImagesTo3D
 A class for processing a pair of stereo images and generateing a disparity image and/or a 3D landmarks map. More...
class  CStereoServerBumblebee
struct  TOdometryOptions
 A structure containing options for the visual odometry. More...
class  CVisualOdometryStereo
 Visual odometry for stereo cameras. More...
struct  TStereoSystemParams
 Parameters associated to a stereo system. More...
struct  TROI
 A structure for storing a 3D ROI. More...
struct  TImageROI
 A structure for defining a ROI within an image. More...
struct  TMatchingOptions
 A structure containing options for the matching. More...

Typedefs

typedef uint64_t TFeatureID
 Definition of a feature ID.
typedef uint64_t TLandmarkID
 Landmark ID.

Enumerations

enum  TFeatureType {
  featSIFT, featKLT, featHarris, featSURF,
  featNotDefined
}
 Types of features. More...
enum  TKLTFeatureStatus {
  statusKLT_IDLE, statusKLT_OOB, statusKLT_SMALL_DET, statusKLT_LARGE_RESIDUE,
  statusKLT_MAX_RESIDUE, statusKLT_TRACKED, statusKLT_MAX_ITERATIONS
}
enum  grabber_dc1394_framerate_t {
  FRAMERATE_1_875 = 32, FRAMERATE_3_75, FRAMERATE_7_5, FRAMERATE_15,
  FRAMERATE_30, FRAMERATE_60, FRAMERATE_120, FRAMERATE_240
}
enum  grabber_dc1394_color_coding_t {
  COLOR_CODING_MONO8 = 352, COLOR_CODING_YUV411, COLOR_CODING_YUV422, COLOR_CODING_YUV444,
  COLOR_CODING_RGB8, COLOR_CODING_MONO16
}
enum  TCameraType {
  CAMERA_CV_AUTODETECT = 0, CAMERA_CV_DC1394, CAMERA_CV_VFL, CAMERA_CV_VFW,
  CAMERA_CV_MIL
}
 These capture types are like their OpenCV equivalents. More...
enum  TColormap { cmGRAYSCALE = 0, cmJET }
 Different colormaps. More...
enum  TInterpolationMethod { imNEAREST = 0, imBILINEAR, imBICUBIC, imAREA }
 Interpolation methods (as defined in OpenCV) Used for OpenCV related operations with images, but also with MRPT native classes. More...

Functions

void MRPTDLLIMPEXP openCV_cross_correlation (const CMRPTImage &img, const CMRPTImage &patch_img, size_t &x_max, size_t &y_max, double &max_val, int x_search_ini=-1, int y_search_ini=-1, int x_search_size=-1, int y_search_size=-1)
 Computes the correlation between this image and another one, encapsulating the openCV function cvMatchTemplate This implementation reduced computation time.
void MRPTDLLIMPEXP flip (CMRPTImage &img)
 Invert an image using OpenCV function.
poses::CPoint3D MRPTDLLIMPEXP pixelTo3D (float x, float y, const CMatrix &A)
 Extract a UNITARY 3D vector in the direction of a 3D point, given from its (x,y) pixels coordinates, and the camera intrinsic coordinates.
CMatrix MRPTDLLIMPEXP buildIntrinsicParamsMatrix (float focalLengthX, float focalLengthY, float centerX, float centerY)
 Builds the intrinsic parameters matrix A from parameters:.
CMatrix MRPTDLLIMPEXP defaultIntrinsicParamsMatrix (unsigned int camIndex=0, unsigned int resolutionX=320, unsigned int resolutionY=240)
 Returns the stored, default intrinsic params matrix for a given camera:.
void MRPTDLLIMPEXP deleteRepeatedFeats (CFeatureList &list)
 Explore the feature list and removes features which are in the same coordinates.
void MRPTDLLIMPEXP rowChecking (CFeatureList &leftList, CFeatureList &rightList, float threshold=0.0)
 Computes ONLY the SIFT descriptors of a set of features .
void MRPTDLLIMPEXP checkTrackedFeatures (CFeatureList &leftList, CFeatureList &rightList, vision::TMatchingOptions options)
 Search for correspondences which are not in the same row and deletes them
void MRPTDLLIMPEXP getDispersion (const CFeatureList &list, vector_float &std, vector_float &mean)
 Computes the dispersion of the features in the image.
void MRPTDLLIMPEXP trackFeatures (const CMRPTImage &inImg1, const CMRPTImage &inImg2, vision::CFeatureList &featureList, const unsigned int &window_width=7, const unsigned int &window_height=7)
 Tracks a set of features in an image.
void MRPTDLLIMPEXP filterBadCorrsByDistance (mrpt::slam::CMetricMap::TMatchingPairList &list, unsigned int numberOfSigmas)
 Filter bad correspondences by distance
void MRPTDLLIMPEXP correctDistortion (CMRPTImage &in_img, CMRPTImage &out_img, CMatrix A, CMatrix dist_coeffs)
 Returns a new image where distortion has been removed.
void MRPTDLLIMPEXP hsv2rgb (float h, float s, float v, float &r, float &g, float &b)
 Transform HSV color components to RGB, all of them in the range [0,1].
void MRPTDLLIMPEXP rgb2hsv (float r, float g, float b, float &h, float &s, float &v)
 Transform RGB color components to HSV, all of them in the range [0,1].
void MRPTDLLIMPEXP colormap (const TColormap &color_map, const float &color_index, float &r, float &g, float &b)
 Transform a float number in the range [0,1] into RGB components.
void MRPTDLLIMPEXP jet2rgb (const float &color_index, float &r, float &g, float &b)
 Computes the RGB color components (range [0,1]) for the corresponding color index in the range [0,1] using the MATLAB 'jet' colormap.
double MRPTDLLIMPEXP computeMsd (const mrpt::slam::CMetricMap::TMatchingPairList &list, const mrpt::poses::CPose3D &Rt)
 Computes the mean squared distance between a set of 3D correspondences
void MRPTDLLIMPEXP cloudsToMatchedList (const mrpt::slam::CObservationVisualLandmarks &cloud1, const mrpt::slam::CObservationVisualLandmarks &cloud2, mrpt::slam::CMetricMap::TMatchingPairList &outList)
 Transform two clouds of 3D points into a matched list of points
float MRPTDLLIMPEXP computeMainOrientation (const CMRPTImage &image, const unsigned int &x, const unsigned int &y)
 Computes the main orientation of a set of points with an image (for using in SIFT-based algorithms).
size_t MRPTDLLIMPEXP matchFeatures (const CFeatureList &list1, const CFeatureList &list2, CMatchedFeatureList &matches, const TMatchingOptions &options=TMatchingOptions())
 Find the matches between two lists of features.
void MRPTDLLIMPEXP projectMatchedFeatures (CMatchedFeatureList &mfList, const vision::TStereoSystemParams &param, mrpt::slam::CLandmarksMap &landmarks)
 Project a list of matched features into the 3D space, using the provided options for the stereo system.

Variables

class MRPTDLLIMPEXP CFeatureList
class MRPTDLLIMPEXP CMatchedFeatureList


Detailed Description

Classes for computer vision, detectors, features, etc.


Typedef Documentation

typedef uint64_t mrpt::vision::TFeatureID

Definition of a feature ID.

Definition at line 44 of file CFeature.h.

typedef uint64_t mrpt::vision::TLandmarkID

Landmark ID.

Definition at line 61 of file vision/utils.h.


Enumeration Type Documentation

Enumerator:
COLOR_CODING_MONO8 
COLOR_CODING_YUV411 
COLOR_CODING_YUV422 
COLOR_CODING_YUV444 
COLOR_CODING_RGB8 
COLOR_CODING_MONO16 

Definition at line 52 of file CImageGrabber_dc1394.h.

Enumerator:
FRAMERATE_1_875 
FRAMERATE_3_75 
FRAMERATE_7_5 
FRAMERATE_15 
FRAMERATE_30 
FRAMERATE_60 
FRAMERATE_120 
FRAMERATE_240 

Definition at line 41 of file CImageGrabber_dc1394.h.

These capture types are like their OpenCV equivalents.

Enumerator:
CAMERA_CV_AUTODETECT 
CAMERA_CV_DC1394 
CAMERA_CV_VFL 
CAMERA_CV_VFW 
CAMERA_CV_MIL 

Definition at line 41 of file CImageGrabber_OpenCV.h.

Different colormaps.

See also:
mrpt::vision::colormap
Enumerator:
cmGRAYSCALE 
cmJET 

Definition at line 423 of file vision/utils.h.

Types of features.

Enumerator:
featSIFT  Scale Invariant Feature Transform [LOWE'04].
featKLT  Kanade-Lucas-Tomasi feature [SHI'94].
featHarris  Harris border and corner detector [HARRIS].
featSURF  Speeded Up Robust Feature [BAY'06].
featNotDefined  Non-defined feature.

Definition at line 47 of file CFeature.h.

Interpolation methods (as defined in OpenCV) Used for OpenCV related operations with images, but also with MRPT native classes.

See also:
mrpt::utils::CMappedImage
Enumerator:
imNEAREST  No interpolation.
imBILINEAR  Bilinear interpolation.
imBICUBIC  Bilinear interpolation.
imAREA  Resampling using pixel-area relation.

Definition at line 451 of file vision/utils.h.

Enumerator:
statusKLT_IDLE  Inactive.
statusKLT_OOB  Out Of Bounds.
statusKLT_SMALL_DET  Determinant of the matrix too small.
statusKLT_LARGE_RESIDUE  Error too big.
statusKLT_MAX_RESIDUE 
statusKLT_TRACKED  Feature correctly tracked.
statusKLT_MAX_ITERATIONS  Iteration maximum reached.

Definition at line 66 of file CFeature.h.


Function Documentation

CMatrix MRPTDLLIMPEXP mrpt::vision::buildIntrinsicParamsMatrix ( float  focalLengthX,
float  focalLengthY,
float  centerX,
float  centerY 
)

Builds the intrinsic parameters matrix A from parameters:.

Parameters:
focalLengthX The focal length, in X (horizontal) pixels
focalLengthY The focal length, in Y (vertical) pixels
centerX The image center, horizontal, in pixels
centerY The image center, vertical, in pixels

This method returns the matrix:
f_x0cX
0f_ycY
001
See also the tutorial discussing the camera model parameters.
See also:
defaultIntrinsicParamsMatrix, pixelTo3D

void MRPTDLLIMPEXP mrpt::vision::checkTrackedFeatures ( CFeatureList &  leftList,
CFeatureList &  rightList,
vision::TMatchingOptions  options 
)

Search for correspondences which are not in the same row and deletes them

..

void MRPTDLLIMPEXP mrpt::vision::cloudsToMatchedList ( const mrpt::slam::CObservationVisualLandmarks cloud1,
const mrpt::slam::CObservationVisualLandmarks cloud2,
mrpt::slam::CMetricMap::TMatchingPairList outList 
)

Transform two clouds of 3D points into a matched list of points

..

void MRPTDLLIMPEXP mrpt::vision::colormap ( const TColormap &  color_map,
const float &  color_index,
float &  r,
float &  g,
float &  b 
)

Transform a float number in the range [0,1] into RGB components.

Different colormaps are available.

float MRPTDLLIMPEXP mrpt::vision::computeMainOrientation ( const CMRPTImage &  image,
const unsigned int &  x,
const unsigned int &  y 
)

Computes the main orientation of a set of points with an image (for using in SIFT-based algorithms).

Parameters:
image (Input). The input image.
x (Input). A vector containing the 'x' coordinates of the image points.
y (Input). A vector containing the 'y' coordinates of the image points.
orientation (Output). A vector containing the main orientation of the image points.

double MRPTDLLIMPEXP mrpt::vision::computeMsd ( const mrpt::slam::CMetricMap::TMatchingPairList list,
const mrpt::poses::CPose3D Rt 
)

Computes the mean squared distance between a set of 3D correspondences

..

void MRPTDLLIMPEXP mrpt::vision::correctDistortion ( CMRPTImage &  in_img,
CMRPTImage &  out_img,
CMatrix  A,
CMatrix  dist_coeffs 
)

Returns a new image where distortion has been removed.

Parameters:
A The 3x3 intrinsic parameters matrix
dist_coeffs The 1x4 vector of distortion coefficients

CMatrix MRPTDLLIMPEXP mrpt::vision::defaultIntrinsicParamsMatrix ( unsigned int  camIndex = 0,
unsigned int  resolutionX = 320,
unsigned int  resolutionY = 240 
)

Returns the stored, default intrinsic params matrix for a given camera:.

Parameters:
camIndex Posible values are listed next.
resolutionX The number of pixel columns
resolutionY The number of pixel rows
The matrix is generated for the indicated camera resolution configuration. The following table summarizes the current supported cameras and the values as ratios of the corresponding horz. or vert. resolution:

camIndex
Manufacturer
Camera model
fx
fy
cx
cy

0
Point Grey Research
Bumblebee
0.79345
1.05793
0.55662
0.52692

1
Sony
???
0.95666094
1.3983423f
0.54626328f
0.4939191f

See also:
buildIntrinsicParamsMatrix, pixelTo3D

void MRPTDLLIMPEXP mrpt::vision::deleteRepeatedFeats ( CFeatureList &  list  ) 

Explore the feature list and removes features which are in the same coordinates.

Parameters:
list (Input). The list of features.

void MRPTDLLIMPEXP mrpt::vision::filterBadCorrsByDistance ( mrpt::slam::CMetricMap::TMatchingPairList list,
unsigned int  numberOfSigmas 
)

Filter bad correspondences by distance

..

void MRPTDLLIMPEXP mrpt::vision::flip ( CMRPTImage &  img  ) 

Invert an image using OpenCV function.

void MRPTDLLIMPEXP mrpt::vision::getDispersion ( const CFeatureList &  list,
vector_float std,
vector_float mean 
)

Computes the dispersion of the features in the image.

Parameters:
list (IN) Inpute list of features
std (OUT) 2 element vector containing the standard deviations in the 'x' and 'y' coordinates.
mean (OUT) 2 element vector containing the mean in the 'x' and 'y' coordinates.

void MRPTDLLIMPEXP mrpt::vision::hsv2rgb ( float  h,
float  s,
float  v,
float &  r,
float &  g,
float &  b 
)

Transform HSV color components to RGB, all of them in the range [0,1].

See also:
rgb2hsv

void MRPTDLLIMPEXP mrpt::vision::jet2rgb ( const float &  color_index,
float &  r,
float &  g,
float &  b 
)

Computes the RGB color components (range [0,1]) for the corresponding color index in the range [0,1] using the MATLAB 'jet' colormap.

See also:
colormap

size_t MRPTDLLIMPEXP mrpt::vision::matchFeatures ( const CFeatureList &  list1,
const CFeatureList &  list2,
CMatchedFeatureList &  matches,
const TMatchingOptions &  options = TMatchingOptions() 
)

Find the matches between two lists of features.

They must be of the same type. Return value: the number of matched pairs of features

Parameters:
list1 (Input). One list.
list2 (Input). Other list.
matches (Output). A vector of pairs of correspondences.
options (Optional Input). A struct containing matching options

void MRPTDLLIMPEXP mrpt::vision::openCV_cross_correlation ( const CMRPTImage &  img,
const CMRPTImage &  patch_img,
size_t &  x_max,
size_t &  y_max,
double &  max_val,
int  x_search_ini = -1,
int  y_search_ini = -1,
int  x_search_size = -1,
int  y_search_size = -1 
)

Computes the correlation between this image and another one, encapsulating the openCV function cvMatchTemplate This implementation reduced computation time.

Parameters:
patch_img The "patch" image, which must be equal, or smaller than "this" image. This function supports gray-scale (1 channel only) images.
x_search_ini The "x" coordinate of the search window.
y_search_ini The "y" coordinate of the search window.
x_search_size The width of the search window.
y_search_size The height of the search window.
x_max The x coordinate where found the maximun cross correlation value.
y_max The y coordinate where found the maximun cross correlation value
max_val The maximun value of cross correlation which we can find Note: By default, the search area is the whole (this) image.
See also:
cross_correlation

poses::CPoint3D MRPTDLLIMPEXP mrpt::vision::pixelTo3D ( float  x,
float  y,
const CMatrix &  A 
)

Extract a UNITARY 3D vector in the direction of a 3D point, given from its (x,y) pixels coordinates, and the camera intrinsic coordinates.

Parameters:
x Pixels coordinates, from the top-left corner of the image.
y Pixels coordinates, from the top-left corner of the image.
A The 3x3 intrinsic parameters matrix for the camera.
See also:
buildIntrinsicParamsMatrix, defaultIntrinsicParamsMatrix

void MRPTDLLIMPEXP mrpt::vision::projectMatchedFeatures ( CMatchedFeatureList &  mfList,
const vision::TStereoSystemParams &  param,
mrpt::slam::CLandmarksMap landmarks 
)

Project a list of matched features into the 3D space, using the provided options for the stereo system.

Parameters:
matches (Input). The list of matched features.
options (Input). The options of the stereo system.
landmarks (Output). A map containing the projected landmarks.

void MRPTDLLIMPEXP mrpt::vision::rgb2hsv ( float  r,
float  g,
float  b,
float &  h,
float &  s,
float &  v 
)

Transform RGB color components to HSV, all of them in the range [0,1].

See also:
hsv2rgb

void MRPTDLLIMPEXP mrpt::vision::rowChecking ( CFeatureList &  leftList,
CFeatureList &  rightList,
float  threshold = 0.0 
)

Computes ONLY the SIFT descriptors of a set of features .

.. ... / void computeSiftDescriptors( const CMRPTImage &in_img, CKanadeLucasTomasi::TKLTFeatureList &in_features, TSIFTFeatureList &out_features); / ** Computes a set of features with the SIFT algorithm... ... / void computeSiftFeatures( const CMRPTImage &in_img, TSIFTFeatureList &out_features, int wantedNumberOfFeatures = 150 );

/ ** Search for correspondences which are not in the same row and deletes them ...

void MRPTDLLIMPEXP mrpt::vision::trackFeatures ( const CMRPTImage &  inImg1,
const CMRPTImage &  inImg2,
vision::CFeatureList &  featureList,
const unsigned int &  window_width = 7,
const unsigned int &  window_height = 7 
)

Tracks a set of features in an image.


Variable Documentation

class MRPTDLLIMPEXP mrpt::vision::CFeatureList

Definition at line 39 of file CFeature.h.

class MRPTDLLIMPEXP mrpt::vision::CMatchedFeatureList

Definition at line 40 of file CFeature.h.




Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN:exported at Mon Jan 12 13:00:16 UTC 2009