Back to list of all libraries | See all modules
mrpt-vision
This library includes some extensions to OpenCV functionality, plus some original classes:
See all the classes in mrpt::vision
Classes | |
class | mrpt::maps::CLandmark |
The class for storing "landmarks" (visual or laser-scan-extracted features,...) More... | |
class | mrpt::maps::CLandmarksMap |
A class for storing a map of 3D probabilistic landmarks. More... | |
class | mrpt::obs::CObservationVisualLandmarks |
Declares a class derived from "CObservation" that stores a Landmarks Map as seen from a stereo camera at a given instant of time. More... | |
class | mrpt::vision::CCamModel |
This class represent a pinhole camera model for Monocular SLAM and implements some associated Jacobians. More... | |
class | mrpt::vision::CDifodo |
This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras. More... | |
class | mrpt::vision::CImagePyramid |
Holds and builds a pyramid of images: starting with an image at full resolution (octave=1), it builds a number of half-resolution images: octave=2 at 1/2 , octave=3 at 1/2^2, octave=N at 1/2^(N-1). More... | |
class | mrpt::vision::CStereoRectifyMap |
Use this class to rectify stereo images if the same distortion maps are reused over and over again. More... | |
class | mrpt::vision::CUndistortMap |
Use this class to undistort monocular images if the same distortion map is used over and over again. More... | |
class | mrpt::vision::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 | mrpt::vision::TFeatureObservation |
One feature observation entry, used within sequences with TSequenceFeatureObservations. More... | |
struct | mrpt::vision::TRelativeFeaturePos |
One relative feature observation entry, used with some relative bundle-adjustment functions. More... | |
struct | mrpt::vision::TSequenceFeatureObservations |
A complete sequence of observations of features from different camera frames (poses). More... | |
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::TMultiResMatchingOutput |
Struct containing the output after matching multi-resolution SIFT-like descriptors. More... | |
struct | mrpt::vision::TMultiResDescMatchOptions |
Struct containing the options when matching multi-resolution SIFT-like descriptors. More... | |
struct | mrpt::vision::TMultiResDescOptions |
Struct containing the options when computing the multi-resolution SIFT-like descriptors. More... | |
Namespaces | |
mrpt::vision::pinhole | |
Functions related to pinhole camera models, point projections, etc. | |
mrpt::vision::pnp | |
Perspective n Point (PnP) Algorithms toolkit for MRPT. | |
mrpt::vision | |
Classes for computer vision, detectors, features, etc. | |
Typedefs | |
typedef uint64_t | mrpt::vision::TFeatureID |
Definition of a feature ID. More... | |
typedef uint64_t | mrpt::vision::TLandmarkID |
Unique IDs for landmarks. More... | |
typedef uint64_t | mrpt::vision::TCameraPoseID |
Unique IDs for camera frames (poses) More... | |
typedef mrpt::aligned_containers< TCameraPoseID, mrpt::poses::CPose3D >::map_t | mrpt::vision::TFramePosesMap |
A list of camera frames (6D poses) indexed by unique IDs. More... | |
typedef mrpt::aligned_containers< mrpt::poses::CPose3D >::vector_t | mrpt::vision::TFramePosesVec |
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs. More... | |
typedef std::map< TLandmarkID, mrpt::math::TPoint3D > | mrpt::vision::TLandmarkLocationsMap |
A list of landmarks (3D points) indexed by unique IDs. More... | |
typedef std::vector< mrpt::math::TPoint3D > | mrpt::vision::TLandmarkLocationsVec |
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs. More... | |
typedef std::map< mrpt::vision::TFeatureID, TRelativeFeaturePos > | mrpt::vision::TRelativeFeaturePosMap |
An index of feature IDs and their relative locations. More... | |
Functions | |
void VISION_IMPEXP | mrpt::vision::pinhole::projectPoints_no_distortion (const std::vector< mrpt::math::TPoint3D > &in_points_3D, const mrpt::poses::CPose3D &cameraPose, const mrpt::math::CMatrixDouble33 &intrinsicParams, std::vector< mrpt::utils::TPixelCoordf > &projectedPoints, bool accept_points_behind=false) |
Project a set of 3D points into a camera at an arbitrary 6D pose using its calibration matrix (undistorted projection model) More... | |
template<bool INVERSE_CAM_POSE> | |
mrpt::utils::TPixelCoordf | mrpt::vision::pinhole::projectPoint_no_distortion (const mrpt::utils::TCamera &cam_params, const mrpt::poses::CPose3D &F, const mrpt::math::TPoint3D &P) |
Project a single 3D point with global coordinates P into a camera at pose F, without distortion parameters. More... | |
template<typename POINT > | |
void | mrpt::vision::pinhole::projectPoint_no_distortion (const POINT &in_point_wrt_cam, const mrpt::utils::TCamera &cam_params, mrpt::utils::TPixelCoordf &out_projectedPoints) |
void VISION_IMPEXP | mrpt::vision::pinhole::projectPoints_with_distortion (const std::vector< mrpt::math::TPoint3D > &in_points_3D, const mrpt::poses::CPose3D &cameraPose, const mrpt::math::CMatrixDouble33 &intrinsicParams, const std::vector< double > &distortionParams, std::vector< mrpt::utils::TPixelCoordf > &projectedPoints, bool accept_points_behind=false) |
Project a set of 3D points into a camera at an arbitrary 6D pose using its calibration matrix and distortion parameters (radial and tangential distortions projection model) More... | |
void VISION_IMPEXP | mrpt::vision::pinhole::projectPoint_with_distortion (const mrpt::math::TPoint3D &in_point_wrt_cam, const mrpt::utils::TCamera &in_cam_params, mrpt::utils::TPixelCoordf &out_projectedPoints, bool accept_points_behind=false) |
Project one 3D point into a camera using its calibration matrix and distortion parameters (radial and tangential distortions projection model) More... | |
void VISION_IMPEXP | mrpt::vision::pinhole::projectPoints_with_distortion (const std::vector< mrpt::math::TPoint3D > &P, const mrpt::utils::TCamera ¶ms, const mrpt::poses::CPose3DQuat &cameraPose, std::vector< mrpt::utils::TPixelCoordf > &pixels, bool accept_points_behind=false) |
void VISION_IMPEXP | mrpt::vision::pinhole::undistort_points (const std::vector< mrpt::utils::TPixelCoordf > &srcDistortedPixels, std::vector< mrpt::utils::TPixelCoordf > &dstUndistortedPixels, const mrpt::math::CMatrixDouble33 &intrinsicParams, const std::vector< double > &distortionParams) |
Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients. More... | |
void VISION_IMPEXP | mrpt::vision::pinhole::undistort_points (const std::vector< mrpt::utils::TPixelCoordf > &srcDistortedPixels, std::vector< mrpt::utils::TPixelCoordf > &dstUndistortedPixels, const mrpt::utils::TCamera &cameraModel) |
Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients. More... | |
void VISION_IMPEXP | mrpt::vision::pinhole::undistort_point (const mrpt::utils::TPixelCoordf &inPt, mrpt::utils::TPixelCoordf &outPt, const mrpt::utils::TCamera &cameraModel) |
Undistort one point given by its pixel coordinates and the camera parameters. More... | |
void VISION_IMPEXP | mrpt::vision::openCV_cross_correlation (const mrpt::utils::CImage &img, const mrpt::utils::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. More... | |
void VISION_IMPEXP | mrpt::vision::flip (mrpt::utils::CImage &img) |
Invert an image using OpenCV function. More... | |
mrpt::math::TPoint3D VISION_IMPEXP | mrpt::vision::pixelTo3D (const mrpt::utils::TPixelCoordf &xy, const mrpt::math::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. More... | |
mrpt::math::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: More... | |
mrpt::math::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: More... | |
void VISION_IMPEXP | mrpt::vision::deleteRepeatedFeats (CFeatureList &list) |
Explore the feature list and removes features which are in the same coordinates. More... | |
void VISION_IMPEXP | mrpt::vision::rowChecking (CFeatureList &leftList, CFeatureList &rightList, float threshold=1.0) |
Search for correspondences which are not in the same row and deletes them. More... | |
void VISION_IMPEXP | mrpt::vision::getDispersion (const CFeatureList &list, mrpt::math::CVectorFloat &std, mrpt::math::CVectorFloat &mean) |
Computes the dispersion of the features in the image. More... | |
double VISION_IMPEXP | mrpt::vision::computeMsd (const mrpt::utils::TMatchingPairList &list, const poses::CPose3D &Rt) |
Computes the mean squared distance between a set of 3D correspondences ... More... | |
void VISION_IMPEXP | mrpt::vision::cloudsToMatchedList (const mrpt::obs::CObservationVisualLandmarks &cloud1, const mrpt::obs::CObservationVisualLandmarks &cloud2, mrpt::utils::TMatchingPairList &outList) |
Transform two clouds of 3D points into a matched list of points ... More... | |
float VISION_IMPEXP | mrpt::vision::computeMainOrientation (const mrpt::utils::CImage &image, unsigned int x, unsigned int y) |
Computes the main orientation of a set of points with an image (for using in SIFT-based algorithms) More... | |
void VISION_IMPEXP | mrpt::vision::normalizeImage (const mrpt::utils::CImage &image, mrpt::utils::CImage &nimage) |
Normalizes the brigthness and contrast of an image by setting its mean value to zero and its standard deviation to unit. More... | |
size_t VISION_IMPEXP | mrpt::vision::matchFeatures (const CFeatureList &list1, const CFeatureList &list2, CMatchedFeatureList &matches, const TMatchingOptions &options=TMatchingOptions(), const TStereoSystemParams ¶ms=TStereoSystemParams()) |
Find the matches between two lists of features which must be of the same type. More... | |
void VISION_IMPEXP | mrpt::vision::generateMask (const CMatchedFeatureList &mList, mrpt::math::CMatrixBool &mask1, mrpt::math::CMatrixBool &mask2, int wSize=10) |
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches. More... | |
double VISION_IMPEXP | mrpt::vision::computeSAD (const mrpt::utils::CImage &patch1, const mrpt::utils::CImage &patch2) |
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches. More... | |
void VISION_IMPEXP | mrpt::vision::addFeaturesToImage (const mrpt::utils::CImage &inImg, const CFeatureList &theList, mrpt::utils::CImage &outImg) |
Draw rectangles around each of the features on a copy of the input image. More... | |
void VISION_IMPEXP | mrpt::vision::projectMatchedFeatures (const CMatchedFeatureList &matches, const mrpt::utils::TStereoCamera &stereo_camera, std::vector< mrpt::math::TPoint3D > &out_points) |
void VISION_IMPEXP | mrpt::vision::projectMatchedFeatures (const CFeatureList &leftList, const CFeatureList &rightList, std::vector< mrpt::math::TPoint3D > &vP3D, const TStereoSystemParams ¶ms=TStereoSystemParams()) |
Computes the 3D position of a set of matched features from their coordinates in the images. More... | |
void VISION_IMPEXP | mrpt::vision::projectMatchedFeature (const CFeaturePtr &leftFeat, const CFeaturePtr &rightFeat, mrpt::math::TPoint3D &p3D, const TStereoSystemParams ¶ms=TStereoSystemParams()) |
Computes the 3D position of a particular matched feature. More... | |
void VISION_IMPEXP | mrpt::vision::projectMatchedFeatures (CMatchedFeatureList &mfList, const TStereoSystemParams ¶m, mrpt::maps::CLandmarksMap &landmarks) |
Project a list of matched features into the 3D space, using the provided parameters of the stereo system. More... | |
void VISION_IMPEXP | mrpt::vision::projectMatchedFeatures (CFeatureList &leftList, CFeatureList &rightList, const TStereoSystemParams ¶m, mrpt::maps::CLandmarksMap &landmarks) |
Project a pair of feature lists into the 3D space, using the provided options for the stereo system. More... | |
void VISION_IMPEXP | mrpt::vision::StereoObs2BRObs (const mrpt::obs::CObservationStereoImages &inObs, const std::vector< double > &sg, mrpt::obs::CObservationBearingRange &outObs) |
Converts a stereo images observation into a bearing and range observation. More... | |
void VISION_IMPEXP | mrpt::vision::StereoObs2BRObs (const CMatchedFeatureList &inMatches, const mrpt::math::CMatrixDouble33 &intrinsicParams, const double &baseline, const mrpt::poses::CPose3D &sensorPose, const std::vector< double > &sg, mrpt::obs::CObservationBearingRange &outObs) |
Converts a matched feature list into a bearing and range observation (some of the stereo camera system must be provided). More... | |
void VISION_IMPEXP | mrpt::vision::StereoObs2BRObs (const mrpt::obs::CObservationVisualLandmarks &inObs, mrpt::obs::CObservationBearingRange &outObs) |
Converts a CObservationVisualLandmarks into a bearing and range observation (without any covariances). More... | |
void VISION_IMPEXP | mrpt::vision::computeStereoRectificationMaps (const mrpt::utils::TCamera &cam1, const mrpt::utils::TCamera &cam2, const mrpt::poses::CPose3D &rightCameraPose, void *outMap1x, void *outMap1y, void *outMap2x, void *outMap2y) |
Computes a pair of x-and-y maps for stereo rectification from a pair of cameras and the relative pose of the second one wrt the first one. More... | |
typedef uint64_t mrpt::vision::TCameraPoseID |
Unique IDs for camera frames (poses)
Definition at line 30 of file vision/include/mrpt/vision/types.h.
typedef uint64_t mrpt::vision::TFeatureID |
Definition of a feature ID.
Definition at line 27 of file vision/include/mrpt/vision/types.h.
typedef mrpt::aligned_containers<TCameraPoseID,mrpt::poses::CPose3D>::map_t mrpt::vision::TFramePosesMap |
A list of camera frames (6D poses) indexed by unique IDs.
Definition at line 32 of file vision/include/mrpt/vision/types.h.
typedef mrpt::aligned_containers<mrpt::poses::CPose3D>::vector_t mrpt::vision::TFramePosesVec |
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs.
Definition at line 33 of file vision/include/mrpt/vision/types.h.
typedef uint64_t mrpt::vision::TLandmarkID |
Unique IDs for landmarks.
Definition at line 29 of file vision/include/mrpt/vision/types.h.
typedef std::map<TLandmarkID,mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsMap |
A list of landmarks (3D points) indexed by unique IDs.
Definition at line 35 of file vision/include/mrpt/vision/types.h.
typedef std::vector<mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsVec |
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
Definition at line 36 of file vision/include/mrpt/vision/types.h.
typedef std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos> mrpt::vision::TRelativeFeaturePosMap |
An index of feature IDs and their relative locations.
Definition at line 107 of file vision/include/mrpt/vision/types.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 59 of file vision/include/mrpt/vision/types.h.
Definition at line 70 of file vision/include/mrpt/vision/types.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.
Enumerator | |
---|---|
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::maps::CLandmark) |
featFAST | FAST feature detector, OpenCV's implementation ("Faster and better: A machine learning approach to corner detection", E. Rosten, R. Porter and T. Drummond, PAMI, 2009). |
featFASTER9 | FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2. |
featFASTER10 | FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2. |
featFASTER12 | FASTER-9 detector, Edward Rosten's libcvd implementation optimized for SSE2. |
featORB | ORB detector and descriptor, OpenCV's implementation ("ORB: an efficient alternative to SIFT or SURF", E. Rublee, V. Rabaud, K. Konolige, G. Bradski, ICCV, 2012). |
Definition at line 41 of file vision/include/mrpt/vision/types.h.
void mrpt::vision::addFeaturesToImage | ( | const mrpt::utils::CImage & | inImg, |
const CFeatureList & | theList, | ||
mrpt::utils::CImage & | outImg | ||
) |
Draw rectangles around each of the features on a copy of the input image.
inImg | [IN] The input image where to draw the features. |
theList | [IN] The list of features. |
outImg | [OUT] The copy of the input image with the marked features. |
Definition at line 912 of file vision_utils.cpp.
References mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), and mrpt::utils::CCanvas::rectangle().
CMatrixDouble33 mrpt::vision::buildIntrinsicParamsMatrix | ( | const double | focalLengthX, |
const double | focalLengthY, | ||
const double | centerX, | ||
const double | centerY | ||
) |
Builds the intrinsic parameters matrix A from parameters:
focalLengthX | [IN] The focal length, in X (horizontal) pixels |
focalLengthY | [IN] The focal length, in Y (vertical) pixels |
centerX | [IN] The image center, horizontal, in pixels |
centerY | [IN] 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.
Definition at line 197 of file vision_utils.cpp.
Referenced by mrpt::vision::defaultIntrinsicParamsMatrix().
void mrpt::vision::cloudsToMatchedList | ( | const mrpt::obs::CObservationVisualLandmarks & | cloud1, |
const mrpt::obs::CObservationVisualLandmarks & | cloud2, | ||
mrpt::utils::TMatchingPairList & | outList | ||
) |
Transform two clouds of 3D points into a matched list of points ...
Definition at line 384 of file vision_utils.cpp.
References mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::begin(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::end(), mrpt::obs::CObservationVisualLandmarks::landmarks, mrpt::maps::CLandmarksMap::landmarks, mrpt::utils::TMatchingPair::other_idx, mrpt::utils::TMatchingPair::other_x, mrpt::utils::TMatchingPair::other_y, mrpt::utils::TMatchingPair::other_z, mrpt::utils::TMatchingPair::this_idx, mrpt::utils::TMatchingPair::this_x, mrpt::utils::TMatchingPair::this_y, and mrpt::utils::TMatchingPair::this_z.
float mrpt::vision::computeMainOrientation | ( | const mrpt::utils::CImage & | image, |
unsigned int | x, | ||
unsigned int | y | ||
) |
Computes the main orientation of a set of points with an image (for using in SIFT-based algorithms)
image | [IN] The input image. |
x | [IN] A vector containing the 'x' coordinates of the image points. |
y | [IN] A vector containing the 'y' coordinates of the image points. |
Definition at line 414 of file vision_utils.cpp.
References MRPT_END, and MRPT_START.
double mrpt::vision::computeMsd | ( | const mrpt::utils::TMatchingPairList & | list, |
const poses::CPose3D & | Rt | ||
) |
Computes the mean squared distance between a set of 3D correspondences ...
Definition at line 359 of file vision_utils.cpp.
References mrpt::poses::CPose3D::getHomogeneousMatrix(), mrpt::math::TPoint3D::norm(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), mrpt::math::TPoint3D::x, mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y(), mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
double mrpt::vision::computeSAD | ( | const mrpt::utils::CImage & | patch1, |
const mrpt::utils::CImage & | patch2 | ||
) |
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches.
Both patches must have the same size.
patch1 | [IN] One patch. |
patch2 | [IN] The other patch. |
Definition at line 888 of file vision_utils.cpp.
References ASSERT_, mrpt::utils::CImage::getAs(), MRPT_END, MRPT_START, and THROW_EXCEPTION.
void mrpt::vision::computeStereoRectificationMaps | ( | const mrpt::utils::TCamera & | cam1, |
const mrpt::utils::TCamera & | cam2, | ||
const mrpt::poses::CPose3D & | rightCameraPose, | ||
void * | outMap1x, | ||
void * | outMap1y, | ||
void * | outMap2x, | ||
void * | outMap2y | ||
) |
Computes a pair of x-and-y maps for stereo rectification from a pair of cameras and the relative pose of the second one wrt the first one.
cam1,cam2 | [IN] The pair of involved cameras |
rightCameraPose | [IN] The change in pose of the second camera wrt the first one |
outMap1x,outMap1y | [OUT] The x-and-y maps corresponding to cam1 (should be converted to *cv::Mat) |
outMap2x,outMap2y | [OUT] The x-and-y maps corresponding to cam2 (should be converted to *cv::Mat) |
Definition at line 1963 of file vision_utils.cpp.
References ASSERT_, mrpt::utils::TCamera::dist, mrpt::poses::CPose3D::getHomogeneousMatrix(), mrpt::utils::TCamera::intrinsicParams, mrpt::utils::TCamera::ncols, mrpt::utils::TCamera::nrows, R, and THROW_EXCEPTION.
CMatrixDouble33 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 | [IN] Posible values are listed next. |
resolutionX | [IN] The number of pixel columns |
resolutionY | [IN] 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:
Definition at line 218 of file vision_utils.cpp.
References mrpt::vision::buildIntrinsicParamsMatrix(), and THROW_EXCEPTION_FMT.
Referenced by mrpt::vision::TStereoSystemParams::TStereoSystemParams().
void mrpt::vision::deleteRepeatedFeats | ( | CFeatureList & | list | ) |
Explore the feature list and removes features which are in the same coordinates.
list | [IN] The list of features. |
Definition at line 253 of file vision_utils.cpp.
References mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), and mrpt::vision::CFeatureList::erase().
void mrpt::vision::flip | ( | mrpt::utils::CImage & | img | ) |
Invert an image using OpenCV function.
Definition at line 157 of file vision_utils.cpp.
References MRPT_END, MRPT_START, and THROW_EXCEPTION.
void mrpt::vision::generateMask | ( | const CMatchedFeatureList & | mList, |
mrpt::math::CMatrixBool & | mask1, | ||
mrpt::math::CMatrixBool & | mask2, | ||
int | wSize = 10 |
||
) |
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches.
Both patches must have the same size.
mList | [IN] The list of matched features. |
mask1 | [OUT] The output mask for left features. |
mask2 | [OUT] The output mask for right features. |
wSize | [IN] The value of the masking window for each features. |
if | mList.size() = 0 |
Definition at line 847 of file vision_utils.cpp.
References ASSERT_, mrpt::math::CMatrixTemplate< T >::getColCount(), mrpt::math::CMatrixTemplate< T >::getRowCount(), and mrpt::math::CMatrixTemplate< T >::set_unsafe().
void mrpt::vision::getDispersion | ( | const CFeatureList & | list, |
mrpt::math::CVectorFloat & | std, | ||
mrpt::math::CVectorFloat & | 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. |
Definition at line 325 of file vision_utils.cpp.
References mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), mean(), mrpt::vision::CFeatureList::size(), and mrpt::math::square().
size_t mrpt::vision::matchFeatures | ( | const CFeatureList & | list1, |
const CFeatureList & | list2, | ||
CMatchedFeatureList & | matches, | ||
const TMatchingOptions & | options = TMatchingOptions() , |
||
const TStereoSystemParams & | params = TStereoSystemParams() |
||
) |
Find the matches between two lists of features which must be of the same type.
list1 | [IN] One list. |
list2 | [IN] Other list. |
matches | [OUT] A vector of pairs of correspondences. |
options | [IN] A struct containing matching options |
Definition at line 460 of file vision_utils.cpp.
References mrpt::vision::TMatchingOptions::addMatches, ASSERT_, mrpt::vision::CFeatureList::begin(), mrpt::vision::bothLists, mrpt::math::TLine2D::coefs, mrpt::math::TLine2D::distance(), mrpt::vision::TMatchingOptions::EDD_RATIO, mrpt::vision::TMatchingOptions::EDSD_RATIO, mrpt::vision::CFeatureList::end(), mrpt::vision::TMatchingOptions::epipolar_TH, mrpt::vision::TMatchingOptions::estimateDepth, FEAT_FREE, mrpt::vision::CFeatureList::get_type(), mrpt::vision::CMatchedFeatureList::getMaxID(), mrpt::vision::TMatchingOptions::hasFundamentalMatrix, mrpt::utils::keep_max(), mrpt::vision::TMatchingOptions::matching_method, mrpt::vision::TMatchingOptions::maxDepthThreshold, mrpt::vision::TMatchingOptions::maxEDD_TH, mrpt::vision::TMatchingOptions::maxEDSD_TH, mrpt::vision::TMatchingOptions::maxORB_dist, mrpt::vision::TMatchingOptions::maxSAD_TH, mrpt::vision::TMatchingOptions::minCC_TH, mrpt::vision::TMatchingOptions::mmCorrelation, mrpt::vision::TMatchingOptions::mmDescriptorORB, mrpt::vision::TMatchingOptions::mmDescriptorSIFT, mrpt::vision::TMatchingOptions::mmDescriptorSURF, mrpt::vision::TMatchingOptions::mmSAD, MRPT_END, MRPT_START, mrpt::vision::openCV_cross_correlation(), mrpt::vision::TMatchingOptions::parallelOpticalAxis, mrpt::vision::projectMatchedFeature(), mrpt::vision::TMatchingOptions::rCC_TH, mrpt::vision::TMatchingOptions::SAD_RATIO, mrpt::vision::CMatchedFeatureList::setLeftMaxID(), mrpt::vision::CMatchedFeatureList::setRightMaxID(), mrpt::vision::CFeatureList::size(), THROW_EXCEPTION, mrpt::vision::TMatchingOptions::useEpipolarRestriction, mrpt::vision::TMatchingOptions::useXRestriction, mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::StereoObs2BRObs().
void mrpt::vision::normalizeImage | ( | const mrpt::utils::CImage & | image, |
mrpt::utils::CImage & | nimage | ||
) |
Normalizes the brigthness and contrast of an image by setting its mean value to zero and its standard deviation to unit.
image | [IN] The input image. |
nimage | [OUTPUT] The new normalized image. |
Definition at line 435 of file vision_utils.cpp.
References ASSERT_, mrpt::utils::CImage::resize(), and mrpt::utils::CImage::setFromMatrix().
Referenced by mrpt::vision::computeHistogramOfOrientations().
void mrpt::vision::openCV_cross_correlation | ( | const mrpt::utils::CImage & | img, |
const mrpt::utils::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.
img | [IN] The imput image. This function supports gray-scale (1 channel only) images. |
patch_img | [IN] The "patch" image, which must be equal, or smaller than "this" image. This function supports gray-scale (1 channel only) images. |
x_max | [OUT] The x coordinate where it was found the maximun cross correlation value. |
y_max | [OUT] The y coordinate where it was found the maximun cross correlation value. |
max_val | [OUT] The maximun value of cross correlation which we can find |
x_search_ini | [IN] The "x" coordinate of the search window. |
y_search_ini | [IN] The "y" coordinate of the search window. |
x_search_size | [IN] The width of the search window. |
y_search_size | [IN] The height of the search window. Note: By default, the search area is the whole (this) image. |
Definition at line 56 of file vision_utils.cpp.
References ASSERT_, mrpt::utils::CImage::extract_patch(), mrpt::utils::CImage::getAs(), mrpt::utils::CImage::getHeight(), mrpt::utils::CImage::getWidth(), mrpt::utils::CImage::grayscale(), mrpt::utils::CImage::isColor(), MRPT_END, MRPT_START, mrpt::utils::round(), mrpt::utils::CImage::setFromImageReadOnly(), mrpt::utils::CImage::setFromIplImageReadOnly(), and THROW_EXCEPTION.
Referenced by mrpt::vision::checkTrackedFeatures(), and mrpt::vision::matchFeatures().
TPoint3D mrpt::vision::pixelTo3D | ( | const mrpt::utils::TPixelCoordf & | xy, |
const mrpt::math::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.
xy | [IN] Pixels coordinates, from the top-left corner of the image. |
A | [IN] The 3x3 intrinsic parameters matrix for the camera. |
Definition at line 175 of file vision_utils.cpp.
References ASSERT_, mrpt::utils::TPixelCoordf::x, and mrpt::utils::TPixelCoordf::y.
Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation().
void mrpt::vision::projectMatchedFeature | ( | const CFeaturePtr & | leftFeat, |
const CFeaturePtr & | rightFeat, | ||
mrpt::math::TPoint3D & | p3D, | ||
const TStereoSystemParams & | params = TStereoSystemParams() |
||
) |
Computes the 3D position of a particular matched feature.
leftList | [IN] The left feature. |
rightList | [IN] The right feature. |
vP3D | [OUT] The 3D position of the projected point. |
params | [IN] The intrinsic and extrinsic parameters of the stereo pair. |
Definition at line 969 of file vision_utils.cpp.
References ASSERT_, mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
Referenced by mrpt::vision::matchFeatures(), and mrpt::vision::projectMatchedFeatures().
void mrpt::vision::projectMatchedFeatures | ( | const CMatchedFeatureList & | matches, |
const mrpt::utils::TStereoCamera & | stereo_camera, | ||
std::vector< mrpt::math::TPoint3D > & | out_points | ||
) |
Definition at line 925 of file vision_utils.cpp.
References mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::utils::TCamera::fx(), mrpt::utils::TStereoCamera::leftCamera, mrpt::utils::TStereoCamera::rightCameraPose, and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x().
Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation().
void mrpt::vision::projectMatchedFeatures | ( | const CFeatureList & | leftList, |
const CFeatureList & | rightList, | ||
std::vector< mrpt::math::TPoint3D > & | vP3D, | ||
const TStereoSystemParams & | params = TStereoSystemParams() |
||
) |
Computes the 3D position of a set of matched features from their coordinates in the images.
The list have to be matched in order, e.g. leftList[0]<->rightList[0]
leftList | [IN] The left list of features. |
rightList | [IN] The right list of features. |
vP3D | [OUT] A vector of mrpt::math::TPoint3D containing the 3D positions of the projected points. |
params | [IN] The intrinsic and extrinsic parameters of the stereo pair. |
Definition at line 949 of file vision_utils.cpp.
References mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), mrpt::vision::projectMatchedFeature(), mrpt::vision::CFeatureList::size(), mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
void mrpt::vision::projectMatchedFeatures | ( | CMatchedFeatureList & | mfList, |
const TStereoSystemParams & | param, | ||
mrpt::maps::CLandmarksMap & | landmarks | ||
) |
Project a list of matched features into the 3D space, using the provided parameters of the stereo system.
mfList | [IN/OUT] The list of matched features. Features which yields a 3D point outside the area defined in TStereoSystemParams are removed from the lists. |
param | [IN] The parameters of the stereo system. |
landmarks | [OUT] A map containing the projected landmarks. |
Definition at line 1074 of file vision_utils.cpp.
References mrpt::maps::CMetricMap::clear(), mrpt::maps::CLandmark::features, mrpt::maps::CLandmark::ID, mrpt::maps::CLandmarksMap::landmarks, MRPT_END, MRPT_START, mrpt::math::TPoint3D::norm(), mrpt::maps::CLandmark::normal, mrpt::maps::CLandmark::pose_cov_11, mrpt::maps::CLandmark::pose_cov_12, mrpt::maps::CLandmark::pose_cov_13, mrpt::maps::CLandmark::pose_cov_22, mrpt::maps::CLandmark::pose_cov_23, mrpt::maps::CLandmark::pose_cov_33, mrpt::maps::CLandmark::pose_mean, mrpt::vision::TStereoSystemParams::Prop_Linear, mrpt::vision::TStereoSystemParams::Prop_SUT, mrpt::vision::TStereoSystemParams::Prop_UT, mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::math::square(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
void mrpt::vision::projectMatchedFeatures | ( | CFeatureList & | leftList, |
CFeatureList & | rightList, | ||
const TStereoSystemParams & | param, | ||
mrpt::maps::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. Features which yields a 3D point outside the area defined in TStereoSystemParams are removed from the lists.
leftList | [IN/OUT] The left list of matched features. |
rightList | [IN/OUT] The right list of matched features. |
param | [IN] The options of the stereo system. |
landmarks | (OUT] A map containing the projected landmarks. |
Definition at line 1372 of file vision_utils.cpp.
References ASSERT_, mrpt::vision::CFeatureList::begin(), mrpt::maps::CMetricMap::clear(), mrpt::vision::CFeatureList::end(), mrpt::vision::CFeatureList::erase(), mrpt::maps::CLandmark::features, mrpt::maps::CLandmark::ID, mrpt::maps::CLandmarksMap::landmarks, MRPT_END, MRPT_START, mrpt::math::TPoint3D::norm(), mrpt::maps::CLandmark::normal, mrpt::maps::CLandmark::pose_cov_11, mrpt::maps::CLandmark::pose_cov_12, mrpt::maps::CLandmark::pose_cov_13, mrpt::maps::CLandmark::pose_cov_22, mrpt::maps::CLandmark::pose_cov_23, mrpt::maps::CLandmark::pose_cov_33, mrpt::maps::CLandmark::pose_mean, mrpt::vision::TStereoSystemParams::Prop_Linear, mrpt::vision::TStereoSystemParams::Prop_SUT, mrpt::vision::TStereoSystemParams::Prop_UT, mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::vision::CFeatureList::size(), mrpt::math::square(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
|
inline |
Project a single 3D point with global coordinates P into a camera at pose F, without distortion parameters.
The template argument INVERSE_CAM_POSE is related on how the camera pose "F" is stored:
Definition at line 52 of file pinhole.h.
References ASSERT_, mrpt::poses::CPose3D::composePoint(), mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::utils::TCamera::fx(), mrpt::utils::TCamera::fy(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 71 of file pinhole.h.
References ASSERT_, mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::utils::TCamera::fx(), mrpt::utils::TCamera::fy(), mrpt::utils::TPixelCoordf::x, and mrpt::utils::TPixelCoordf::y.
void mrpt::vision::pinhole::projectPoint_with_distortion | ( | const mrpt::math::TPoint3D & | in_point_wrt_cam, |
const mrpt::utils::TCamera & | in_cam_params, | ||
mrpt::utils::TPixelCoordf & | out_projectedPoints, | ||
bool | accept_points_behind = false |
||
) |
Project one 3D point into a camera using its calibration matrix and distortion parameters (radial and tangential distortions projection model)
in_point_wrt_cam | [IN] The 3D point wrt the camera focus, with +Z=optical axis, +X=righthand in the image plane, +Y=downward in the image plane. |
in_cam_params | [IN] The camera parameters. See http://www.mrpt.org/Camera_Parameters |
out_projectedPoints | [OUT] The projected point, in pixel units. |
accept_points_behind | [IN] See the note below. |
Definition at line 295 of file pinhole.cpp.
References MRPT_UNUSED_PARAM, mrpt::math::square(), mrpt::utils::TPixelCoordf::x, mrpt::math::TPoint3D::x, mrpt::utils::TPixelCoordf::y, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
void mrpt::vision::pinhole::projectPoints_no_distortion | ( | const std::vector< mrpt::math::TPoint3D > & | in_points_3D, |
const mrpt::poses::CPose3D & | cameraPose, | ||
const mrpt::math::CMatrixDouble33 & | intrinsicParams, | ||
std::vector< mrpt::utils::TPixelCoordf > & | projectedPoints, | ||
bool | accept_points_behind = false |
||
) |
Project a set of 3D points into a camera at an arbitrary 6D pose using its calibration matrix (undistorted projection model)
in_points_3D | [IN] The list of 3D points in world coordinates (meters) to project. |
cameraPose | [IN] The pose of the camera in the world. |
intrinsicParams | [IN] The 3x3 calibration matrix. See http://www.mrpt.org/Camera_Parameters |
projectedPoints | [OUT] The list of image coordinates (in pixels) for the projected points. At output this list is resized to the same number of input points. |
accept_points_behind | [IN] See the note below. |
Definition at line 33 of file pinhole.cpp.
References MRPT_END, MRPT_START, and mrpt::vision::pinhole::projectPoints_with_distortion().
Referenced by mrpt::vision::checkerBoardCameraCalibration().
void mrpt::vision::pinhole::projectPoints_with_distortion | ( | const std::vector< mrpt::math::TPoint3D > & | in_points_3D, |
const mrpt::poses::CPose3D & | cameraPose, | ||
const mrpt::math::CMatrixDouble33 & | intrinsicParams, | ||
const std::vector< double > & | distortionParams, | ||
std::vector< mrpt::utils::TPixelCoordf > & | projectedPoints, | ||
bool | accept_points_behind = false |
||
) |
Project a set of 3D points into a camera at an arbitrary 6D pose using its calibration matrix and distortion parameters (radial and tangential distortions projection model)
in_points_3D | [IN] The list of 3D points in world coordinates (meters) to project. |
cameraPose | [IN] The pose of the camera in the world. |
intrinsicParams | [IN] The 3x3 calibration matrix. See http://www.mrpt.org/Camera_Parameters |
distortionParams | [IN] The 4-length vector with the distortion parameters [k1 k2 p1 p2]. See http://www.mrpt.org/Camera_Parameters |
projectedPoints | [OUT] The list of image coordinates (in pixels) for the projected points. At output this list is resized to the same number of input points. |
accept_points_behind | [IN] See the note below. |
Definition at line 58 of file pinhole.cpp.
References ASSERT_, mrpt::poses::CPose3D::inverseComposePoint(), MRPT_END, MRPT_START, and THROW_EXCEPTION.
Referenced by mrpt::vision::checkerBoardCameraCalibration(), mrpt::vision::checkerBoardStereoCalibration(), and mrpt::vision::pinhole::projectPoints_no_distortion().
void mrpt::vision::pinhole::projectPoints_with_distortion | ( | const std::vector< mrpt::math::TPoint3D > & | P, |
const mrpt::utils::TCamera & | params, | ||
const mrpt::poses::CPose3DQuat & | cameraPose, | ||
std::vector< mrpt::utils::TPixelCoordf > & | pixels, | ||
bool | accept_points_behind = false |
||
) |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 247 of file pinhole.cpp.
References mrpt::poses::CPose3DQuat::inverseComposePoint(), MRPT_END, MRPT_START, mrpt::math::square(), mrpt::math::TPoint3D::x, mrpt::math::TPoint3D::y, and mrpt::math::TPoint3D::z.
void mrpt::vision::rowChecking | ( | CFeatureList & | leftList, |
CFeatureList & | rightList, | ||
float | threshold = 1.0 |
||
) |
Search for correspondences which are not in the same row and deletes them.
leftList | [IN/OUT] The left list of matched features. |
rightList | [IN/OUT] The right list of matched features. |
threshold | [IN] The tolerance value for the row checking: valid matched are within this threshold. |
Definition at line 287 of file vision_utils.cpp.
References ASSERT_, mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), mrpt::vision::CFeatureList::erase(), and mrpt::vision::CFeatureList::size().
void mrpt::vision::StereoObs2BRObs | ( | const mrpt::obs::CObservationStereoImages & | inObs, |
const std::vector< double > & | sg, | ||
mrpt::obs::CObservationBearingRange & | outObs | ||
) |
Converts a stereo images observation into a bearing and range observation.
Converts a CObservationVisualLandmarks into a bearing and range observation (without any covariances).
inObs | [IN] The input stereo images observation. |
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). |
Fields of view are not computed.
inObs | [IN] The input observation. |
sg | [IN] The sigma of the row, col, and disparity variables involved in the feature detection. |
outObs | [OUT] The output bearing and range observation. |
Definition at line 1799 of file vision_utils.cpp.
References mrpt::obs::CObservationStereoImages::cameraPose, mrpt::obs::CObservationBearingRange::TMeasurement::covariance, mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::vision::CFeatureExtraction::detectFeatures(), mrpt::obs::CObservationBearingRange::fieldOfView_pitch, mrpt::obs::CObservationBearingRange::fieldOfView_yaw, mrpt::utils::TCamera::fx(), mrpt::obs::CObservationStereoImages::imageLeft, mrpt::obs::CObservationStereoImages::imageRight, mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID, mrpt::obs::CObservationStereoImages::leftCamera, mrpt::vision::matchFeatures(), MRPT_UNUSED_PARAM, mrpt::obs::CObservationBearingRange::TMeasurement::pitch, mrpt::obs::CObservationBearingRange::TMeasurement::range, mrpt::obs::CObservationStereoImages::rightCameraPose, mrpt::obs::CObservationBearingRange::sensedData, mrpt::obs::CObservationBearingRange::setSensorPose(), mrpt::math::square(), mrpt::obs::CObservationBearingRange::validCovariances, mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.
void mrpt::vision::StereoObs2BRObs | ( | const CMatchedFeatureList & | inMatches, |
const mrpt::math::CMatrixDouble33 & | intrinsicParams, | ||
const double & | baseline, | ||
const mrpt::poses::CPose3D & | sensorPose, | ||
const std::vector< double > & | sg, | ||
mrpt::obs::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). |
Definition at line 1679 of file vision_utils.cpp.
References mrpt::obs::CObservationBearingRange::TMeasurement::covariance, mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID, mrpt::obs::CObservationBearingRange::TMeasurement::pitch, mrpt::obs::CObservationBearingRange::TMeasurement::range, mrpt::obs::CObservationBearingRange::sensedData, mrpt::obs::CObservationBearingRange::setSensorPose(), mrpt::math::square(), mrpt::obs::CObservationBearingRange::validCovariances, and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.
void mrpt::vision::StereoObs2BRObs | ( | const mrpt::obs::CObservationVisualLandmarks & | inObs, |
mrpt::obs::CObservationBearingRange & | outObs | ||
) |
Converts a CObservationVisualLandmarks into a bearing and range observation (without any covariances).
Fields of view are not computed.
inObs | [IN] The input observation. |
outObs | [OUT] The output bearing and range observation. |
Definition at line 1938 of file vision_utils.cpp.
References mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::begin(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::end(), mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID, mrpt::obs::CObservationVisualLandmarks::landmarks, mrpt::maps::CLandmarksMap::landmarks, mrpt::obs::CObservationBearingRange::TMeasurement::pitch, mrpt::obs::CObservationBearingRange::TMeasurement::range, mrpt::obs::CObservationBearingRange::sensedData, mrpt::math::square(), and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.
void mrpt::vision::pinhole::undistort_point | ( | const mrpt::utils::TPixelCoordf & | inPt, |
mrpt::utils::TPixelCoordf & | outPt, | ||
const mrpt::utils::TCamera & | cameraModel | ||
) |
Undistort one point given by its pixel coordinates and the camera parameters.
Definition at line 205 of file pinhole.cpp.
References mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::utils::TCamera::dist, mrpt::utils::TCamera::fx(), mrpt::utils::TCamera::fy(), MRPT_END, MRPT_START, mrpt::utils::TPixelCoordf::x, and mrpt::utils::TPixelCoordf::y.
void mrpt::vision::pinhole::undistort_points | ( | const std::vector< mrpt::utils::TPixelCoordf > & | srcDistortedPixels, |
std::vector< mrpt::utils::TPixelCoordf > & | dstUndistortedPixels, | ||
const mrpt::math::CMatrixDouble33 & | intrinsicParams, | ||
const std::vector< double > & | distortionParams | ||
) |
Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients.
srcDistortedPixels | [IN] The pixel coordinates as in the distorted image. |
dstUndistortedPixels | [OUT] The computed pixel coordinates without distortion. |
intrinsicParams | [IN] The 3x3 calibration matrix. See http://www.mrpt.org/Camera_Parameters |
distortionParams | [IN] The 4-length vector with the distortion parameters [k1 k2 p1 p2]. See http://www.mrpt.org/Camera_Parameters |
Definition at line 142 of file pinhole.cpp.
References ASSERT_, mrpt::utils::TCamera::dist, and mrpt::utils::TCamera::intrinsicParams.
Referenced by mrpt::vision::CCamModel::undistort_point().
void mrpt::vision::pinhole::undistort_points | ( | const std::vector< mrpt::utils::TPixelCoordf > & | srcDistortedPixels, |
std::vector< mrpt::utils::TPixelCoordf > & | dstUndistortedPixels, | ||
const mrpt::utils::TCamera & | cameraModel | ||
) |
Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients.
srcDistortedPixels | [IN] The pixel coordinates as in the distorted image. |
dstUndistortedPixels | [OUT] The computed pixel coordinates without distortion. |
cameraModel | [IN] The camera parameters. |
Definition at line 155 of file pinhole.cpp.
References mrpt::utils::TCamera::cx(), mrpt::utils::TCamera::cy(), mrpt::utils::TCamera::dist, mrpt::utils::TCamera::fx(), mrpt::utils::TCamera::fy(), MRPT_END, and MRPT_START.
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |