|
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...
|
Namespaces |
namespace | mrpt |
| The main namespace for all the Mobile Robot Programming Toolkit (MRPT) C++ 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::poses |
| Classes for 2D/3D geometry representation, both of single values and probability density distributions (PDFs) in many forms.
|
namespace | mrpt::vision |
| Classes for computer vision, detectors, features, etc.
|
Typedefs |
typedef uint64_t | mrpt::vision::TLandmarkID |
| Landmark ID.
|
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 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 | mrpt::vision::flip (CMRPTImage &img) |
| Invert an image using OpenCV function.
|
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.
|
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 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 | mrpt::vision::filterBadCorrsByDistance (mrpt::slam::CMetricMap::TMatchingPairList &list, unsigned int numberOfSigmas) |
| Filter bad correspondences by distance
|
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.
|
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 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 | 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.
|