Classes for computer vision, detectors, features, etc. More...
Namespaces | |
| namespace | pinhole |
Functions related to pinhole camera models, point projections, etc. | |
Classes | |
| class | CCamModel |
| This class represent a pinhole camera model for Monocular SLAM and implements some associated Jacobians. More... | |
| class | CFeature |
| A generic 2D feature from an image, extracted with CFeatureExtraction Each feature may have one or more descriptors (see descriptors), in addition to an image patch. More... | |
| class | CFeatureList |
| A list of features. More... | |
| class | CMatchedFeatureList |
| A list of features. More... | |
| class | CFeatureExtraction |
| The central class from which images can be analyzed in search of different kinds of interest points and descriptors computed for them. More... | |
| class | CVideoFileWriter |
| An output stream which takes a sequence of images and writes a video file in any of a given of compatible formats. 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... | |
| struct | TImageCalibData |
| Data associated to each image in the calibration process mrpt::vision::checkerBoardCameraCalibration (All the information can be left empty and will be filled up in the calibration method). More... | |
Typedefs | |
| typedef uint64_t | TFeatureID |
| Definition of a feature ID. | |
| typedef uint64_t | TLandmarkID |
| Landmark ID. | |
| typedef std::map< std::string, TImageCalibData > | TCalibrationImageList |
| A list of images, used in checkerBoardCameraCalibration. | |
Enumerations | |
| enum | TFeatureType { featNotDefined = -1, featKLT = 0, featHarris, featBCD, featSIFT, featSURF, featBeacon, featFAST } |
Types of features - This means that the point has been detected with this algorithm, which is independent of additional descriptors a feature may also have. More... | |
| enum | TDescriptorType { descAny = 0, descSIFT = 1, descSURF = 2, descSpinImages = 4, descPolarImages = 8, descLogPolarImages = 16 } |
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescriptors to indicate which descriptors are to be computed for features. More... | |
| enum | TKLTFeatureStatus { statusKLT_IDLE, statusKLT_OOB, statusKLT_SMALL_DET, statusKLT_LARGE_RESIDUE, statusKLT_MAX_RESIDUE, statusKLT_TRACKED, statusKLT_MAX_ITERATIONS } |
Functions | |
| void VISION_IMPEXP | openCV_cross_correlation (const CImage &img, const CImage &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 VISION_IMPEXP | flip (CImage &img) |
| Invert an image using OpenCV function. | |
| TPoint3D VISION_IMPEXP | pixelTo3D (const vision::TPixelCoordf &xy, const CMatrixDouble33 &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. | |
| CMatrixDouble33 VISION_IMPEXP | buildIntrinsicParamsMatrix (const double focalLengthX, const double focalLengthY, const double centerX, const double centerY) |
| Builds the intrinsic parameters matrix A from parameters:. | |
| CMatrixDouble33 VISION_IMPEXP | 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 VISION_IMPEXP | deleteRepeatedFeats (CFeatureList &list) |
| Explore the feature list and removes features which are in the same coordinates. | |
| void VISION_IMPEXP | rowChecking (CFeatureList &leftList, CFeatureList &rightList, float threshold=0.0) |
| Search for correspondences which are not in the same row and deletes them | |
| void VISION_IMPEXP | checkTrackedFeatures (CFeatureList &leftList, CFeatureList &rightList, vision::TMatchingOptions options) |
| Search for correspondences which are not in the same row and deletes them | |
| void VISION_IMPEXP | getDispersion (const CFeatureList &list, vector_float &std, vector_float &mean) |
| Computes the dispersion of the features in the image. | |
| void VISION_IMPEXP | trackFeatures2 (const CImage &inImg1, const CImage &inImg2, CFeatureList &featureList, const unsigned int &window_width=15, const unsigned int &window_height=15) |
| Tracks a set of features in an image. | |
| void VISION_IMPEXP | trackFeatures (const CImage &inImg1, const CImage &inImg2, vision::CFeatureList &featureList, const unsigned int &window_width=15, const unsigned int &window_height=15) |
| Tracks a set of features in an image. | |
| void VISION_IMPEXP | trackFeatures (const CImage &inImg1, const CImage &inImg2, const CFeatureList &inFeatureList, CFeatureList &outFeatureList, const unsigned int &window_width, const unsigned int &window_height) |
| Tracks a set of features in an image. | |
| void VISION_IMPEXP | filterBadCorrsByDistance (mrpt::utils::TMatchingPairList &list, unsigned int numberOfSigmas) |
| Filter bad correspondences by distance | |
| void | correctDistortion (const CImage &in_img, CImage &out_img, const CMatrixDouble33 &A, const vector_double &dist_coeffs) |
| Returns a new image where distortion has been removed. | |
| double VISION_IMPEXP | computeMsd (const mrpt::utils::TMatchingPairList &list, const mrpt::poses::CPose3D &Rt) |
| Computes the mean squared distance between a set of 3D correspondences | |
| void VISION_IMPEXP | cloudsToMatchedList (const mrpt::slam::CObservationVisualLandmarks &cloud1, const mrpt::slam::CObservationVisualLandmarks &cloud2, mrpt::utils::TMatchingPairList &outList) |
| Transform two clouds of 3D points into a matched list of points | |
| float VISION_IMPEXP | computeMainOrientation (const CImage &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 VISION_IMPEXP | matchFeatures (const CFeatureList &list1, const CFeatureList &list2, CMatchedFeatureList &matches, const TMatchingOptions &options=TMatchingOptions()) |
| Find the matches between two lists of features. | |
| size_t VISION_IMPEXP | matchFeatures2 (const CFeatureList &list1, const CFeatureList &list2, CMatchedFeatureList &matches, const TMatchingOptions &options=TMatchingOptions()) |
| Find the matches between two lists of features. | |
| void VISION_IMPEXP | addFeaturesToImage (const CImage &inImg, const CFeatureList &theList, CImage &outImg) |
| void VISION_IMPEXP | projectMatchedFeatures (CMatchedFeatureList &mfList, const vision::TStereoSystemParams ¶m, mrpt::slam::CLandmarksMap &landmarks) |
| Project a list of matched features into the 3D space, using the provided options for the stereo system. | |
| void VISION_IMPEXP | projectMatchedFeatures (CFeatureList &leftList, CFeatureList &rightList, const vision::TStereoSystemParams ¶m, mrpt::slam::CLandmarksMap &landmarks) |
| Project a pair of feature lists into the 3D space, using the provided options for the stereo system. | |
| bool VISION_IMPEXP | checkerBoardCameraCalibration (TCalibrationImageList &images, unsigned int check_size_x, unsigned int check_size_y, double check_squares_length_X_meters, double check_squares_length_Y_meters, CMatrixDouble33 &intrinsicParams, std::vector< double > &distortionParams, bool normalize_image=true, double *out_MSE=NULL, bool skipDrawDetectedImgs=false) |
| Performs a camera calibration (computation of projection and distortion parameters) from a sequence of captured images of a checkerboard. | |
| void VISION_IMPEXP | StereoObs2BRObs (const CObservationStereoImages &inObs, const std::vector< double > &sg, CObservationBearingRange &outObs) |
| Converts a stereo images observation into a bearing and range observation. | |
| void VISION_IMPEXP | StereoObs2BRObs (const CMatchedFeatureList &inMatches, const CMatrixDouble33 &intrinsicParams, const double &baseline, const CPose3D &sensorPose, const std::vector< double > &sg, CObservationBearingRange &outObs) |
| Converts a matched feature list into a bearing and range observation (some of the stereo camera system must be provided). | |
Classes for computer vision, detectors, features, etc.
| typedef std::map<std::string,TImageCalibData> mrpt::vision::TCalibrationImageList |
A list of images, used in checkerBoardCameraCalibration.
Definition at line 517 of file vision/include/mrpt/vision/utils.h.
| typedef uint64_t mrpt::vision::TFeatureID |
Definition of a feature ID.
Definition at line 46 of file CFeature.h.
| typedef uint64_t mrpt::vision::TLandmarkID |
Landmark ID.
Definition at line 68 of file vision/include/mrpt/vision/utils.h.
The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescriptors to indicate which descriptors are to be computed for features.
Definition at line 68 of file CFeature.h.
Types of features - This means that the point has been detected with this algorithm, which is independent of additional descriptors a feature may also have.
| featNotDefined |
Non-defined feature (also used for Occupancy features). |
| featKLT |
Kanade-Lucas-Tomasi feature [SHI'94]. |
| featHarris |
Harris border and corner detector [HARRIS]. |
| featBCD |
Binary corder detector. |
| featSIFT |
Scale Invariant Feature Transform [LOWE'04]. |
| featSURF |
Speeded Up Robust Feature [BAY'06]. |
| featBeacon |
A especial case: this is not an image feature, but a 2D/3D beacon (used for range-only SLAM from mrpt::slam::CLandmark). |
| featFAST |
FAST feature detector ("Faster and better: A machine learning approach to corner detection", E. Rosten, R. Porter and T. Drummond, PAMI, 2009). |
Definition at line 54 of file CFeature.h.
Definition at line 78 of file CFeature.h.
| void VISION_IMPEXP mrpt::vision::addFeaturesToImage | ( | const CImage & | inImg, | |
| const CFeatureList & | theList, | |||
| CImage & | outImg | |||
| ) |
| CMatrixDouble33 VISION_IMPEXP mrpt::vision::buildIntrinsicParamsMatrix | ( | const double | focalLengthX, | |
| const double | focalLengthY, | |||
| const double | centerX, | |||
| const double | centerY | |||
| ) |
Builds the intrinsic parameters matrix A from 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_x | 0 | cX |
0 | f_y | cY |
0 | 0 | 1 |
See also the tutorial discussing the camera model parameters.
| bool VISION_IMPEXP mrpt::vision::checkerBoardCameraCalibration | ( | TCalibrationImageList & | images, | |
| unsigned int | check_size_x, | |||
| unsigned int | check_size_y, | |||
| double | check_squares_length_X_meters, | |||
| double | check_squares_length_Y_meters, | |||
| CMatrixDouble33 & | intrinsicParams, | |||
| std::vector< double > & | distortionParams, | |||
| bool | normalize_image = true, |
|||
| double * | out_MSE = NULL, |
|||
| bool | skipDrawDetectedImgs = false | |||
| ) |
Performs a camera calibration (computation of projection and distortion parameters) from a sequence of captured images of a checkerboard.
| input_images | [IN/OUT] At input, this list must have one entry for each image to process. At output the original, detected checkboard and rectified images can be found here. See TImageCalibData. | |
| check_size_x | [IN] The number of squares in the checkerboard in the X direction. | |
| check_size_y | [IN] The number of squares in the checkerboard in the Y direction. | |
| check_squares_length_X_meters | [IN] The size of each square in the checkerboard, in meters, in the X axis. | |
| check_squares_length_Y_meters | [IN] This will typically be equal to check_squares_length_X_meters. | |
| intrinsicParams | [OUT] The 3x3 intrinsic parameters matrix. See http://www.mrpt.org/Camera_Parameters | |
| distortionParams | [OUT] The 1x4 vector of distortion parameters: k1 k2 p1 p2. See http://www.mrpt.org/Camera_Parameters | |
| normalize_image | [IN] Select OpenCV flag | |
| out_MSE | [OUT] If set to !=NULL, the mean square error of the reprojection will be stored here (in pixel units). | |
| skipDrawDetectedImgs | [IN] Whether to skip the generation of the undistorted and detected images in each TImageCalibData |
| void VISION_IMPEXP mrpt::vision::checkTrackedFeatures | ( | CFeatureList & | leftList, | |
| CFeatureList & | rightList, | |||
| vision::TMatchingOptions | options | |||
| ) |
Search for correspondences which are not in the same row and deletes them
..
| void VISION_IMPEXP mrpt::vision::cloudsToMatchedList | ( | const mrpt::slam::CObservationVisualLandmarks & | cloud1, | |
| const mrpt::slam::CObservationVisualLandmarks & | cloud2, | |||
| mrpt::utils::TMatchingPairList & | outList | |||
| ) |
Transform two clouds of 3D points into a matched list of points
..
| float VISION_IMPEXP mrpt::vision::computeMainOrientation | ( | const CImage & | 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).
| 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 VISION_IMPEXP mrpt::vision::computeMsd | ( | const mrpt::utils::TMatchingPairList & | list, | |
| const mrpt::poses::CPose3D & | Rt | |||
| ) |
Computes the mean squared distance between a set of 3D correspondences
..
| void mrpt::vision::correctDistortion | ( | const CImage & | in_img, | |
| CImage & | out_img, | |||
| const CMatrixDouble33 & | A, | |||
| const vector_double & | dist_coeffs | |||
| ) | [inline] |
Returns a new image where distortion has been removed.
| A | The 3x3 intrinsic parameters matrix | |
| dist_coeffs | The 1x4 (or 1x5) vector of distortion coefficients |
Definition at line 418 of file vision/include/mrpt/vision/utils.h.
References mrpt::utils::CImage::rectifyImage().
| CMatrixDouble33 VISION_IMPEXP 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:.
| 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:
| void VISION_IMPEXP mrpt::vision::deleteRepeatedFeats | ( | CFeatureList & | list | ) |
Explore the feature list and removes features which are in the same coordinates.
| list | (Input). The list of features. |
| void VISION_IMPEXP mrpt::vision::filterBadCorrsByDistance | ( | mrpt::utils::TMatchingPairList & | list, | |
| unsigned int | numberOfSigmas | |||
| ) |
Filter bad correspondences by distance
..
| void VISION_IMPEXP mrpt::vision::flip | ( | CImage & | img | ) |
Invert an image using OpenCV function.
| void VISION_IMPEXP mrpt::vision::getDispersion | ( | const CFeatureList & | list, | |
| vector_float & | std, | |||
| vector_float & | mean | |||
| ) |
Computes the dispersion of the features in the image.
| list | (IN) Input 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. |
| size_t VISION_IMPEXP 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
| list1 | (Input). One list. | |
| list2 | (Input). Other list. | |
| matches | (Output). A vector of pairs of correspondences. | |
| options | (Optional Input). A struct containing matching options |
| size_t VISION_IMPEXP mrpt::vision::matchFeatures2 | ( | 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
| 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 VISION_IMPEXP mrpt::vision::openCV_cross_correlation | ( | const CImage & | img, | |
| const CImage & | 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.
| 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. |
| TPoint3D VISION_IMPEXP mrpt::vision::pixelTo3D | ( | const vision::TPixelCoordf & | xy, | |
| const CMatrixDouble33 & | 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.
| 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. |
| void VISION_IMPEXP mrpt::vision::projectMatchedFeatures | ( | CFeatureList & | leftList, | |
| CFeatureList & | rightList, | |||
| const vision::TStereoSystemParams & | param, | |||
| mrpt::slam::CLandmarksMap & | landmarks | |||
| ) |
Project a pair of feature lists into the 3D space, using the provided options for the stereo system.
The matches must be in order, i.e. leftList[0] corresponds to rightList[0] and so on;
| leftList | (Input). The left list of matched features. | |
| rightList | (Input). The right list of matched features. | |
| options | (Input). The options of the stereo system. | |
| landmarks | (Output). A map containing the projected landmarks. |
| void VISION_IMPEXP mrpt::vision::projectMatchedFeatures | ( | CMatchedFeatureList & | mfList, | |
| const vision::TStereoSystemParams & | param, | |||
| mrpt::slam::CLandmarksMap & | landmarks | |||
| ) |
| void VISION_IMPEXP mrpt::vision::rowChecking | ( | CFeatureList & | leftList, | |
| CFeatureList & | rightList, | |||
| float | threshold = 0.0 | |||
| ) |
Search for correspondences which are not in the same row and deletes them
..
| void VISION_IMPEXP mrpt::vision::StereoObs2BRObs | ( | const CMatchedFeatureList & | inMatches, | |
| const CMatrixDouble33 & | intrinsicParams, | |||
| const double & | baseline, | |||
| const CPose3D & | sensorPose, | |||
| const std::vector< double > & | sg, | |||
| CObservationBearingRange & | outObs | |||
| ) |
Converts a matched feature list into a bearing and range observation (some of the stereo camera system must be provided).
| inMatches | [IN] The input list of matched features. | |
| intrinsicParams | [IN] The intrisic params of the reference (left) camera of the stereo system. | |
| baseline | [IN] The distance among the X axis of the right camera wrt the reference (left) camera. | |
| sg | [IN] The sigma of the row, col, and disparity variables involved in the feature detection. | |
| outObs | [OUT] The output bearing and range observation (including covariances). |
| void VISION_IMPEXP mrpt::vision::StereoObs2BRObs | ( | const CObservationStereoImages & | inObs, | |
| const std::vector< double > & | sg, | |||
| CObservationBearingRange & | outObs | |||
| ) |
Converts a stereo images observation into a bearing and range observation.
| inObs | [IN] The input stereo images observation. | |
| outObs | [OUT] The output bearing and range observation (including covariances). | |
| sg | [IN] The sigma of the row, col, and disparity variables involved in the feature detection. |
| void VISION_IMPEXP mrpt::vision::trackFeatures | ( | const CImage & | inImg1, | |
| const CImage & | inImg2, | |||
| const CFeatureList & | inFeatureList, | |||
| CFeatureList & | outFeatureList, | |||
| const unsigned int & | window_width, | |||
| const unsigned int & | window_height | |||
| ) |
Tracks a set of features in an image.
| void VISION_IMPEXP mrpt::vision::trackFeatures | ( | const CImage & | inImg1, | |
| const CImage & | inImg2, | |||
| vision::CFeatureList & | featureList, | |||
| const unsigned int & | window_width = 15, |
|||
| const unsigned int & | window_height = 15 | |||
| ) |
Tracks a set of features in an image.
| void VISION_IMPEXP mrpt::vision::trackFeatures2 | ( | const CImage & | inImg1, | |
| const CImage & | inImg2, | |||
| CFeatureList & | featureList, | |||
| const unsigned int & | window_width = 15, |
|||
| const unsigned int & | window_height = 15 | |||
| ) |
Tracks a set of features in an image.
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |