#include <mrpt/vision/CFeature.h>
#include <mrpt/utils/CImage.h>
#include <mrpt/math/utils.h>
#include <mrpt/utils/CLoadableOptions.h>
#include <mrpt/slam/CMetricMap.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/poses/CPoint2D.h>
#include <mrpt/poses/CPoint3D.h>
Go to the source code of this file.
Classes | |
struct | mrpt::vision::TStereoSystemParams |
Parameters associated to a stereo system. More... | |
struct | mrpt::vision::TROI |
A structure for storing a 3D ROI. More... | |
struct | mrpt::vision::TImageROI |
A structure for defining a ROI within an image. More... | |
struct | mrpt::vision::TMatchingOptions |
A structure containing options for the matching. More... | |
struct | mrpt::vision::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... | |
Namespaces | |
namespace | mrpt |
This is the global namespace for all Mobile Robot Porgramming Toolkit (MRPT) libraries. | |
namespace | mrpt::slam |
This namespace contains algorithms for SLAM, localization, map building, representation of robot's actions and observations, and representation of many kinds of metric maps. | |
namespace | mrpt::vision |
Classes for computer vision, detectors, features, etc. | |
Typedefs | |
typedef uint64_t | mrpt::vision::TLandmarkID |
Landmark ID. | |
typedef std::map< std::string, TImageCalibData > | mrpt::vision::TCalibrationImageList |
A list of images, used in checkerBoardCameraCalibration. | |
Enumerations | |
enum | mrpt::vision::TColormap { mrpt::vision::cmGRAYSCALE = 0, mrpt::vision::cmJET } |
Different colormaps. More... | |
enum | mrpt::vision::TInterpolationMethod { mrpt::vision::imNEAREST = 0, mrpt::vision::imBILINEAR, mrpt::vision::imBICUBIC, mrpt::vision::imAREA } |
Interpolation methods (as defined in OpenCV) Used for OpenCV related operations with images, but also with MRPT native classes. More... | |
Functions | |
void MRPTDLLIMPEXP | 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. | |
void MRPTDLLIMPEXP | mrpt::vision::flip (CImage &img) |
Invert an image using OpenCV function. | |
TPoint3D MRPTDLLIMPEXP | mrpt::vision::pixelTo3D (const vision::TPixelCoordf &xy, const CMatrixFloat &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 | mrpt::vision::buildIntrinsicParamsMatrix (float focalLengthX, float focalLengthY, float centerX, float centerY) |
Builds the intrinsic parameters matrix A from parameters:. | |
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:. | |
void MRPTDLLIMPEXP | mrpt::vision::deleteRepeatedFeats (CFeatureList &list) |
Explore the feature list and removes features which are in the same coordinates. | |
void MRPTDLLIMPEXP | mrpt::vision::rowChecking (CFeatureList &leftList, CFeatureList &rightList, float threshold=0.0) |
Computes ONLY the SIFT descriptors of a set of features . | |
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::getDispersion (const CFeatureList &list, vector_float &std, vector_float &mean) |
Computes the dispersion of the features in the image. | |
void MRPTDLLIMPEXP | mrpt::vision::trackFeatures (const CImage &inImg1, const CImage &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 | mrpt::vision::filterBadCorrsByDistance (mrpt::slam::CMetricMap::TMatchingPairList &list, unsigned int numberOfSigmas) |
Filter bad correspondences by distance | |
void MRPTDLLIMPEXP | mrpt::vision::correctDistortion (CImage &in_img, CImage &out_img, CMatrix A, CMatrix dist_coeffs) |
Returns a new image where distortion has been removed. | |
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]. | |
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]. | |
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. | |
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. | |
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::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 | 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). | |
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. | |
void MRPTDLLIMPEXP | mrpt::vision::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. | |
bool MRPTDLLIMPEXP | 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, CMatrixDouble &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. |
Page generated by Doxygen 1.5.9 for MRPT 0.7.1 SVN: at Mon Aug 17 22:21:34 EDT 2009 |