MRPT  2.0.2
Classes | Modules | Typedefs | Enumerations | Functions
[mrpt-vision]

Detailed Description

Computer vision algorithms.

Back to list of all libraries | See all modules

Library `mrpt-vision`

[New in MRPT 2.0.0]

This library is part of MRPT but has no dependencies, so it can be installed in Debian-based systems with:

    sudo apt install libmrpt-vision-dev

See: Using MRPT from your CMake project

This library includes some extensions to OpenCV functionality, plus some original classes:

See all the classes in mrpt::vision

Collaboration diagram for [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::CDifodo
 This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras. More...
 
class  mrpt::vision::CFeatureLines
 This class wraps different line detectors and descriptors from OpenCV. 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...
 

Modules

 Feature detection, descriptors and matching
 
 KD-Tree construction of visual
 descriptors
 
 Bundle-Adjustment methods
 
 Chessboard calibration
 
 Perspective-n-Point pose estimation
 
 Feature detection and tracking
 

Typedefs

using mrpt::vision::TFeatureID = uint64_t
 Definition of a feature ID. More...
 
using mrpt::vision::TLandmarkID = uint64_t
 Unique IDs for landmarks. More...
 
using mrpt::vision::TCameraPoseID = uint64_t
 Unique IDs for camera frames (poses) More...
 
using mrpt::vision::TFramePosesMap = std::map< TCameraPoseID, mrpt::poses::CPose3D >
 A list of camera frames (6D poses) indexed by unique IDs. More...
 
using mrpt::vision::TFramePosesVec = std::vector< mrpt::poses::CPose3D >
 A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs. More...
 
using mrpt::vision::TLandmarkLocationsMap = std::map< TLandmarkID, mrpt::math::TPoint3D >
 A list of landmarks (3D points) indexed by unique IDs. More...
 
using mrpt::vision::TLandmarkLocationsVec = std::vector< mrpt::math::TPoint3D >
 A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs. More...
 
using mrpt::vision::TRelativeFeaturePosMap = std::map< mrpt::vision::TFeatureID, TRelativeFeaturePos >
 An index of feature IDs and their relative locations. More...
 

Enumerations

enum  mrpt::vision::TKeyPointMethod : int8_t {
  mrpt::vision::featNotDefined = -1, mrpt::vision::featKLT = 0, mrpt::vision::featHarris = 1, mrpt::vision::featSIFT = 3,
  mrpt::vision::featSURF = 4, mrpt::vision::featBeacon = 5, mrpt::vision::featFAST = 6, mrpt::vision::featORB = 10,
  mrpt::vision::featAKAZE = 11, mrpt::vision::featLSD = 12
}
 Types of key point detectors. More...
 
enum  mrpt::vision::TDescriptorType : uint16_t {
  mrpt::vision::descAny = 0, mrpt::vision::descSIFT = 1, mrpt::vision::descSURF = 2, mrpt::vision::descSpinImages = 4,
  mrpt::vision::descPolarImages = 8, mrpt::vision::descLogPolarImages = 16, mrpt::vision::descORB = 32, mrpt::vision::descBLD = 64,
  mrpt::vision::descLATCH = 128
}
 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  mrpt::vision::TFeatureTrackStatus : uint8_t { mrpt::vision::status_IDLE = 0, mrpt::vision::status_TRACKED = 5, mrpt::vision::status_OOB = 1, mrpt::vision::status_LOST = 10 }
 

Functions

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::img::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::img::TPixelCoordf mrpt::vision::pinhole::projectPoint_no_distortion (const mrpt::img::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::img::TCamera &cam_params, mrpt::img::TPixelCoordf &out_projectedPoints)
 
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::img::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 mrpt::vision::pinhole::projectPoint_with_distortion (const mrpt::math::TPoint3D &in_point_wrt_cam, const mrpt::img::TCamera &in_cam_params, mrpt::img::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 mrpt::vision::pinhole::projectPoints_with_distortion (const std::vector< mrpt::math::TPoint3D > &P, const mrpt::img::TCamera &params, const mrpt::poses::CPose3DQuat &cameraPose, std::vector< mrpt::img::TPixelCoordf > &pixels, bool accept_points_behind=false)
 
void mrpt::vision::pinhole::undistort_points (const std::vector< mrpt::img::TPixelCoordf > &srcDistortedPixels, std::vector< mrpt::img::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 mrpt::vision::pinhole::undistort_points (const std::vector< mrpt::img::TPixelCoordf > &srcDistortedPixels, std::vector< mrpt::img::TPixelCoordf > &dstUndistortedPixels, const mrpt::img::TCamera &cameraModel)
 Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients. More...
 
void mrpt::vision::pinhole::undistort_point (const mrpt::img::TPixelCoordf &inPt, mrpt::img::TPixelCoordf &outPt, const mrpt::img::TCamera &cameraModel)
 Undistort one point given by its pixel coordinates and the camera parameters. More...
 
void mrpt::vision::openCV_cross_correlation (const mrpt::img::CImage &img, const mrpt::img::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...
 
mrpt::math::TPoint3D mrpt::vision::pixelTo3D (const mrpt::img::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 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 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...
 
double mrpt::vision::computeMsd (const mrpt::tfest::TMatchingPairList &list, const poses::CPose3D &Rt)
 Computes the mean squared distance between a set of 3D correspondences ... More...
 
void mrpt::vision::cloudsToMatchedList (const mrpt::obs::CObservationVisualLandmarks &cloud1, const mrpt::obs::CObservationVisualLandmarks &cloud2, mrpt::tfest::TMatchingPairList &outList)
 Transform two clouds of 3D points into a matched list of points ... More...
 
float mrpt::vision::computeMainOrientation (const mrpt::img::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 mrpt::vision::normalizeImage (const mrpt::img::CImage &image, mrpt::img::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 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. More...
 
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. More...
 
double mrpt::vision::computeSAD (const mrpt::img::CImage &patch1, const mrpt::img::CImage &patch2)
 Calculates the Sum of Absolutes Differences (range [0,1]) between two patches. More...
 
void mrpt::vision::addFeaturesToImage (const mrpt::img::CImage &inImg, const CFeatureList &theList, mrpt::img::CImage &outImg)
 Draw rectangles around each of the features on a copy of the input image. More...
 
void mrpt::vision::projectMatchedFeatures (const CMatchedFeatureList &matches, const mrpt::img::TStereoCamera &stereo_camera, std::vector< mrpt::math::TPoint3D > &out_points)
 
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. More...
 
void mrpt::vision::projectMatchedFeature (const CFeature &leftFeat, const CFeature &rightFeat, mrpt::math::TPoint3D &p3D, const TStereoSystemParams &params=TStereoSystemParams())
 Computes the 3D position of a particular matched feature. More...
 
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. More...
 
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. More...
 
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. More...
 
void mrpt::vision::StereoObs2BRObs (const CMatchedFeatureList &inMatches, const mrpt::math::CMatrixDouble33 &intrinsicParams, 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 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 mrpt::vision::computeStereoRectificationMaps (const mrpt::img::TCamera &cam1, const mrpt::img::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 Documentation

◆ TCameraPoseID

using mrpt::vision::TCameraPoseID = typedef uint64_t

Unique IDs for camera frames (poses)

Definition at line 29 of file vision/include/mrpt/vision/types.h.

◆ TFeatureID

using mrpt::vision::TFeatureID = typedef uint64_t

Definition of a feature ID.

Definition at line 24 of file vision/include/mrpt/vision/types.h.

◆ TFramePosesMap

A list of camera frames (6D poses) indexed by unique IDs.

Definition at line 32 of file vision/include/mrpt/vision/types.h.

◆ TFramePosesVec

using mrpt::vision::TFramePosesVec = typedef std::vector<mrpt::poses::CPose3D>

A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs.

Definition at line 35 of file vision/include/mrpt/vision/types.h.

◆ TLandmarkID

using mrpt::vision::TLandmarkID = typedef uint64_t

Unique IDs for landmarks.

Definition at line 27 of file vision/include/mrpt/vision/types.h.

◆ TLandmarkLocationsMap

A list of landmarks (3D points) indexed by unique IDs.

Definition at line 38 of file vision/include/mrpt/vision/types.h.

◆ TLandmarkLocationsVec

A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.

Definition at line 41 of file vision/include/mrpt/vision/types.h.

◆ TRelativeFeaturePosMap

An index of feature IDs and their relative locations.

Definition at line 160 of file vision/include/mrpt/vision/types.h.

Enumeration Type Documentation

◆ TDescriptorType

The bitwise OR combination of values of TDescriptorType are used in CFeatureExtraction::computeDescriptors to indicate which descriptors are to be computed for features.

Enumerator
descAny 

Used in some methods to mean "any of the present descriptors".

descSIFT 

SIFT descriptors.

descSURF 

SURF descriptors.

descSpinImages 

Intensity-domain spin image descriptors.

descPolarImages 

Polar image descriptor.

descLogPolarImages 

Log-Polar image descriptor.

descORB 

Bit-based feature descriptor.

descBLD 

BLD Line descriptor.

descLATCH 

LATCH Line descriptor.

Definition at line 76 of file vision/include/mrpt/vision/types.h.

◆ TFeatureTrackStatus

Enumerator
status_IDLE 

Inactive (right after detection, and before being tried to track)

status_TRACKED 

Feature correctly tracked.

status_OOB 

Feature fell Out Of Bounds (out of the image limits, too close to image borders)

status_LOST 

Unable to track this feature (mismatch is too high for the given tracking window: lack of texture? oclussion?)

Definition at line 97 of file vision/include/mrpt/vision/types.h.

◆ TKeyPointMethod

Types of key point detectors.

Enumerator
featNotDefined 

Non-defined feature (also used for Occupancy features)

featKLT 

Kanade-Lucas-Tomasi feature [SHI'94].

featHarris 

Harris border and corner detector [HARRIS].

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).

featORB 

ORB detector and descriptor, OpenCV's implementation.

featAKAZE 

AKAZE detector, OpenCV's implementation.

featLSD 

LSD detector, OpenCV's implementation.

Definition at line 44 of file vision/include/mrpt/vision/types.h.

Function Documentation

◆ addFeaturesToImage()

void mrpt::vision::addFeaturesToImage ( const mrpt::img::CImage inImg,
const CFeatureList theList,
mrpt::img::CImage outImg 
)

Draw rectangles around each of the features on a copy of the input image.

Parameters
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 757 of file vision_utils.cpp.

References mrpt::img::CCanvas::rectangle().

Here is the call graph for this function:

◆ buildIntrinsicParamsMatrix()

CMatrixDouble33 mrpt::vision::buildIntrinsicParamsMatrix ( const double  focalLengthX,
const double  focalLengthY,
const double  centerX,
const double  centerY 
)

Builds the intrinsic parameters matrix A from parameters:

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_x0cX
0f_ycY
001

See also the tutorial discussing the camera model parameters.

See also
defaultIntrinsicParamsMatrix, pixelTo3D

Definition at line 157 of file vision_utils.cpp.

Referenced by mrpt::vision::defaultIntrinsicParamsMatrix().

Here is the caller graph for this function:

◆ cloudsToMatchedList()

void mrpt::vision::cloudsToMatchedList ( const mrpt::obs::CObservationVisualLandmarks cloud1,
const mrpt::obs::CObservationVisualLandmarks cloud2,
mrpt::tfest::TMatchingPairList outList 
)

◆ computeMainOrientation()

float mrpt::vision::computeMainOrientation ( const mrpt::img::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)

Parameters
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.
Returns
The main orientation of the image point.

Definition at line 271 of file vision_utils.cpp.

References mrpt::img::CImage::getHeight(), mrpt::img::CImage::getWidth(), MRPT_END, and MRPT_START.

Here is the call graph for this function:

◆ computeMsd()

double mrpt::vision::computeMsd ( const mrpt::tfest::TMatchingPairList list,
const poses::CPose3D Rt 
)

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

Definition at line 213 of file vision_utils.cpp.

References mrpt::poses::CPose3D::getHomogeneousMatrix(), mrpt::math::TPoint3D_< T >::norm(), mrpt::math::TPoint3D_data< T >::x, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), mrpt::math::TPoint3D_data< T >::y, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y(), and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ computeSAD()

double mrpt::vision::computeSAD ( const mrpt::img::CImage patch1,
const mrpt::img::CImage patch2 
)

Calculates the Sum of Absolutes Differences (range [0,1]) between two patches.

Both patches must have the same size.

Parameters
patch1[IN] One patch.
patch2[IN] The other patch.
Returns
The value of computed SAD normalized to [0,1]

Definition at line 736 of file vision_utils.cpp.

References ASSERT_, mrpt::img::CImage::at(), mrpt::img::CImage::getHeight(), mrpt::img::CImage::getSize(), mrpt::img::CImage::getWidth(), MRPT_END, MRPT_START, and THROW_EXCEPTION.

Here is the call graph for this function:

◆ computeStereoRectificationMaps()

void mrpt::vision::computeStereoRectificationMaps ( const mrpt::img::TCamera cam1,
const mrpt::img::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.

Parameters
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)
See also
An easier to use class for stereo rectification mrpt::vision::CStereoRectifyMap

Definition at line 1819 of file vision_utils.cpp.

References ASSERT_, mrpt::img::TCamera::dist, mrpt::poses::CPose3D::getHomogeneousMatrix(), mrpt::img::TCamera::intrinsicParams, mrpt::img::TCamera::ncols, mrpt::img::TCamera::nrows, R, and THROW_EXCEPTION.

Here is the call graph for this function:

◆ defaultIntrinsicParamsMatrix()

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:

Parameters
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:

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

Definition at line 176 of file vision_utils.cpp.

References mrpt::vision::buildIntrinsicParamsMatrix(), and THROW_EXCEPTION_FMT.

Referenced by mrpt::vision::TStereoSystemParams::TStereoSystemParams().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ generateMask()

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.

Parameters
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.
Exceptions
ifmList.size() = 0

Definition at line 700 of file vision_utils.cpp.

References ASSERT_, mrpt::math::CMatrixDynamic< T >::cols(), and mrpt::math::CMatrixDynamic< T >::rows().

Here is the call graph for this function:

◆ matchFeatures()

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.

Parameters
list1[IN] One list.
list2[IN] Other list.
matches[OUT] A vector of pairs of correspondences.
options[IN] A struct containing matching options
Returns
Returns the number of matched pairs of features.

Definition at line 315 of file vision_utils.cpp.

References mrpt::vision::TMatchingOptions::addMatches, ASSERT_, mrpt::img::CImage::at(), 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, mrpt::img::FAST_REF_OR_CONVERT_TO_GRAY, FEAT_FREE, mrpt::vision::CFeatureList::get_type(), mrpt::img::CImage::getHeight(), mrpt::vision::CMatchedFeatureList::getMaxID(), mrpt::img::CImage::getWidth(), mrpt::vision::TMatchingOptions::hasFundamentalMatrix, mrpt::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, params, 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_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::StereoObs2BRObs().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ normalizeImage()

void mrpt::vision::normalizeImage ( const mrpt::img::CImage image,
mrpt::img::CImage nimage 
)

Normalizes the brigthness and contrast of an image by setting its mean value to zero and its standard deviation to unit.

Parameters
image[IN] The input image.
nimage[OUTPUT] The new normalized image.

Definition at line 292 of file vision_utils.cpp.

References ASSERT_, mrpt::math::CMatrixDynamic< T >::cols(), mrpt::img::CImage::getAsMatrix(), mrpt::img::CImage::getChannelCount(), mrpt::img::CImage::getHeight(), mrpt::img::CImage::getWidth(), mrpt::math::meanAndStd(), mrpt::img::CImage::resize(), mrpt::math::CMatrixDynamic< T >::resize(), mrpt::math::CMatrixDynamic< T >::rows(), and mrpt::img::CImage::setFromMatrix().

Here is the call graph for this function:

◆ openCV_cross_correlation()

void mrpt::vision::openCV_cross_correlation ( const mrpt::img::CImage img,
const mrpt::img::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.

Parameters
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.
See also
cross_correlation

Definition at line 49 of file vision_utils.cpp.

References mrpt::img::CImage::asCvMat(), ASSERT_, mrpt::img::CImage::extract_patch(), mrpt::img::CImage::getHeight(), mrpt::img::CImage::getWidth(), mrpt::img::CImage::grayscale(), mrpt::img::CImage::isColor(), mrpt::img::CImage::makeShallowCopy(), MRPT_END, MRPT_START, mrpt::round(), mrpt::img::SHALLOW_COPY, and THROW_EXCEPTION.

Referenced by mrpt::vision::matchFeatures(), and mrpt::vision::CFeature::patchCorrelationTo().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pixelTo3D()

TPoint3D mrpt::vision::pixelTo3D ( const mrpt::img::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.

Parameters
xy[IN] Pixels coordinates, from the top-left corner of the image.
A[IN] The 3x3 intrinsic parameters matrix for the camera.
Returns
The mrpt::math::TPoint3D containing the output unitary vector.
See also
buildIntrinsicParamsMatrix, defaultIntrinsicParamsMatrix, TPixelCoordf

Definition at line 137 of file vision_utils.cpp.

References ASSERT_, mrpt::math::TPoint3D_< T >::norm(), mrpt::img::TPixelCoordf::x, mrpt::math::TPoint3D_data< T >::x, mrpt::img::TPixelCoordf::y, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ projectMatchedFeature()

void mrpt::vision::projectMatchedFeature ( const CFeature leftFeat,
const CFeature rightFeat,
mrpt::math::TPoint3D p3D,
const TStereoSystemParams params = TStereoSystemParams() 
)

Computes the 3D position of a particular matched feature.

Parameters
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 813 of file vision_utils.cpp.

References ASSERT_, mrpt::vision::CFeature::keypoint, params, mrpt::vision::TKeyPoint_templ< PIXEL_COORD_TYPE >::pt, mrpt::img::TPixelCoordf::x, mrpt::math::TPoint3D_data< T >::x, mrpt::img::TPixelCoordf::y, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Referenced by mrpt::vision::matchFeatures(), and mrpt::vision::projectMatchedFeatures().

Here is the caller graph for this function:

◆ projectMatchedFeatures() [1/4]

void mrpt::vision::projectMatchedFeatures ( const CMatchedFeatureList matches,
const mrpt::img::TStereoCamera stereo_camera,
std::vector< mrpt::math::TPoint3D > &  out_points 
)

Definition at line 770 of file vision_utils.cpp.

References mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TStereoCamera::leftCamera, mrpt::img::TStereoCamera::rightCameraPose, and mrpt::math::TPose3DQuat::x.

Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ projectMatchedFeatures() [2/4]

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]

Parameters
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 794 of file vision_utils.cpp.

References mrpt::vision::CFeatureList::begin(), mrpt::vision::CFeatureList::end(), params, mrpt::vision::projectMatchedFeature(), mrpt::vision::CFeatureList::size(), mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ projectMatchedFeatures() [3/4]

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.

Parameters
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.
See also
TStereoSystemParams, CLandmarksMap

Definition at line 925 of file vision_utils.cpp.

References mrpt::math::CVectorDynamic< T >::asEigen(), mrpt::math::CMatrixDynamic< T >::asEigen(), mrpt::vision::TStereoSystemParams::baseline, mrpt::math::MatrixBase< Scalar, Derived >::chol(), mrpt::maps::CMetricMap::clear(), mrpt::vision::TStereoSystemParams::factor_a, mrpt::vision::TStereoSystemParams::factor_b, mrpt::vision::TStereoSystemParams::factor_k, mrpt::maps::CLandmark::features, mrpt::math::MatrixVectorBase< Scalar, Derived >::fill(), mrpt::maps::CLandmark::ID, mrpt::vision::TStereoSystemParams::K, mrpt::maps::CLandmarksMap::landmarks, mrpt::vision::TStereoSystemParams::maxZ, mrpt::vision::TStereoSystemParams::minZ, MRPT_END, MRPT_START, mrpt::math::TPoint3D_< T >::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::CVectorDynamic< T >::resize(), mrpt::math::MatrixBase< Scalar, Derived >::row(), mrpt::square(), mrpt::vision::TStereoSystemParams::stdDisp, mrpt::vision::TStereoSystemParams::stdPixel, mrpt::math::MatrixVectorBase< Scalar, Derived >::transpose(), mrpt::vision::TStereoSystemParams::uncPropagation, mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ projectMatchedFeatures() [4/4]

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.

Parameters
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.
See also
TStereoSystemParams, CLandmarksMap

Definition at line 1252 of file vision_utils.cpp.

References mrpt::math::CVectorDynamic< T >::asEigen(), mrpt::math::CMatrixDynamic< T >::asEigen(), ASSERT_, mrpt::vision::TStereoSystemParams::baseline, mrpt::vision::CFeatureList::begin(), mrpt::math::MatrixBase< Scalar, Derived >::chol(), mrpt::maps::CMetricMap::clear(), mrpt::math::MatrixBase< Scalar, Derived >::col(), mrpt::vision::CFeatureList::end(), mrpt::vision::CFeatureList::erase(), mrpt::vision::TStereoSystemParams::factor_a, mrpt::vision::TStereoSystemParams::factor_b, mrpt::vision::TStereoSystemParams::factor_k, mrpt::maps::CLandmark::features, mrpt::math::MatrixVectorBase< Scalar, Derived >::fill(), mrpt::maps::CLandmark::ID, mrpt::vision::TStereoSystemParams::K, mrpt::maps::CLandmarksMap::landmarks, mrpt::vision::TStereoSystemParams::maxZ, mrpt::vision::TStereoSystemParams::minZ, MRPT_END, MRPT_START, mrpt::math::TPoint3D_< T >::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::CVectorDynamic< T >::resize(), mrpt::math::MatrixBase< Scalar, Derived >::row(), mrpt::vision::CFeatureList::size(), mrpt::square(), mrpt::vision::TStereoSystemParams::stdDisp, mrpt::vision::TStereoSystemParams::stdPixel, mrpt::math::MatrixVectorBase< Scalar, Derived >::transpose(), mrpt::vision::TStereoSystemParams::uncPropagation, mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ projectPoint_no_distortion() [1/2]

template<bool INVERSE_CAM_POSE>
mrpt::img::TPixelCoordf mrpt::vision::pinhole::projectPoint_no_distortion ( const mrpt::img::TCamera cam_params,
const mrpt::poses::CPose3D F,
const mrpt::math::TPoint3D P 
)
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:

  • INVERSE_CAM_POSE:false -> The local coordinates of the feature wrt the camera F are: $ P \ominus F $
  • INVERSE_CAM_POSE:true -> The local coordinates of the feature wrt the camera F are: $ F \oplus P $

Definition at line 63 of file pinhole.h.

References ASSERT_, mrpt::poses::CPose3D::composePoint(), mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ projectPoint_no_distortion() [2/2]

template<typename POINT >
void mrpt::vision::pinhole::projectPoint_no_distortion ( const POINT &  in_point_wrt_cam,
const mrpt::img::TCamera cam_params,
mrpt::img::TPixelCoordf out_projectedPoints 
)
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 81 of file pinhole.h.

References ASSERT_, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), mrpt::img::TPixelCoordf::x, and mrpt::img::TPixelCoordf::y.

Here is the call graph for this function:

◆ projectPoint_with_distortion()

void mrpt::vision::pinhole::projectPoint_with_distortion ( const mrpt::math::TPoint3D in_point_wrt_cam,
const mrpt::img::TCamera in_cam_params,
mrpt::img::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)

Parameters
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 https://www.mrpt.org/Camera_Parameters
out_projectedPoints[OUT] The projected point, in pixel units.
accept_points_behind[IN] See the note below.
Note
Points "behind" the camera (which couldn't be physically seen in the real world) are marked with pixel coordinates (-1,-1) to detect them as invalid, unless accept_points_behind is true. In that case they'll be projected normally.
See also
projectPoints_with_distortion

◆ projectPoints_no_distortion()

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::img::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)

Parameters
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 https://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.
Note
Points "behind" the camera (which couldn't be physically seen in the real world) are marked with pixel coordinates (-1,-1) to detect them as invalid, unless accept_points_behind is true. In that case they'll be projected normally.
See also
projectPoints_with_distortion, projectPoint_no_distortion

Definition at line 31 of file pinhole.cpp.

References MRPT_END, MRPT_START, and mrpt::vision::pinhole::projectPoints_with_distortion().

Here is the call graph for this function:

◆ projectPoints_with_distortion() [1/2]

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::img::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)

Parameters
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 https://www.mrpt.org/Camera_Parameters
distortionParams[IN] The 4-length vector with the distortion parameters [k1 k2 p1 p2]. See https://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.
Note
Points "behind" the camera (which couldn't be physically seen in the real world) are marked with pixel coordinates (-1,-1) to detect them as invalid, unless accept_points_behind is true. In that case they'll be projected normally.
See also
projectPoint_with_distortion, projectPoints_no_distortion

Definition at line 51 of file pinhole.cpp.

References ASSERT_, mrpt::math::CMatrixFixed< T, ROWS, COLS >::cols(), mrpt::d2f(), mrpt::poses::CPose3D::inverseComposePoint(), MRPT_END, MRPT_START, mrpt::math::CMatrixFixed< T, ROWS, COLS >::rows(), and THROW_EXCEPTION.

Referenced by mrpt::vision::checkerBoardStereoCalibration(), and mrpt::vision::pinhole::projectPoints_no_distortion().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ projectPoints_with_distortion() [2/2]

void mrpt::vision::pinhole::projectPoints_with_distortion ( const std::vector< mrpt::math::TPoint3D > &  P,
const mrpt::img::TCamera params,
const mrpt::poses::CPose3DQuat cameraPose,
std::vector< mrpt::img::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 250 of file pinhole.cpp.

References mrpt::d2f(), mrpt::poses::CPose3DQuat::inverseComposePoint(), MRPT_END, MRPT_START, params, mrpt::square(), mrpt::math::TPoint3D_data< T >::x, mrpt::math::TPoint3D_data< T >::y, and mrpt::math::TPoint3D_data< T >::z.

Here is the call graph for this function:

◆ StereoObs2BRObs() [1/3]

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).

Parameters
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.

Parameters
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 1672 of file vision_utils.cpp.

References mrpt::obs::CObservationStereoImages::cameraPose, mrpt::obs::CObservationBearingRange::TMeasurement::covariance, mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::vision::CFeatureExtraction::detectFeatures(), mrpt::obs::CObservationBearingRange::fieldOfView_pitch, mrpt::obs::CObservationBearingRange::fieldOfView_yaw, mrpt::img::TCamera::fx(), mrpt::obs::CObservationStereoImages::imageLeft, mrpt::obs::CObservationStereoImages::imageRight, mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID, mrpt::obs::CObservationStereoImages::leftCamera, mrpt::vision::matchFeatures(), mrpt::math::multiply_HCHt(), mrpt::obs::CObservationBearingRange::TMeasurement::pitch, mrpt::obs::CObservationBearingRange::TMeasurement::range, mrpt::obs::CObservationStereoImages::rightCameraPose, mrpt::obs::CObservationBearingRange::sensedData, mrpt::obs::CObservationBearingRange::setSensorPose(), mrpt::square(), mrpt::obs::CObservationBearingRange::validCovariances, mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.

Here is the call graph for this function:

◆ StereoObs2BRObs() [2/3]

void mrpt::vision::StereoObs2BRObs ( const CMatchedFeatureList inMatches,
const mrpt::math::CMatrixDouble33 intrinsicParams,
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).

Parameters
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 1578 of file vision_utils.cpp.

References mrpt::obs::CObservationBearingRange::TMeasurement::covariance, mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID, mrpt::math::multiply_HCHt(), mrpt::obs::CObservationBearingRange::TMeasurement::pitch, mrpt::obs::CObservationBearingRange::TMeasurement::range, mrpt::obs::CObservationBearingRange::sensedData, mrpt::obs::CObservationBearingRange::setSensorPose(), mrpt::square(), mrpt::obs::CObservationBearingRange::validCovariances, and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.

Here is the call graph for this function:

◆ StereoObs2BRObs() [3/3]

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.

Parameters
inObs[IN] The input observation.
outObs[OUT] The output bearing and range observation.

Definition at line 1790 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::square(), and mrpt::obs::CObservationBearingRange::TMeasurement::yaw.

Here is the call graph for this function:

◆ undistort_point()

void mrpt::vision::pinhole::undistort_point ( const mrpt::img::TPixelCoordf inPt,
mrpt::img::TPixelCoordf outPt,
const mrpt::img::TCamera cameraModel 
)

Undistort one point given by its pixel coordinates and the camera parameters.

See also
undistort_points

Definition at line 204 of file pinhole.cpp.

References mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::d2f(), mrpt::img::TCamera::dist, mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), MRPT_END, MRPT_START, mrpt::img::TPixelCoordf::x, and mrpt::img::TPixelCoordf::y.

Here is the call graph for this function:

◆ undistort_points() [1/2]

void mrpt::vision::pinhole::undistort_points ( const std::vector< mrpt::img::TPixelCoordf > &  srcDistortedPixels,
std::vector< mrpt::img::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.

Parameters
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 https://www.mrpt.org/Camera_Parameters
distortionParams[IN] The 4-length vector with the distortion parameters [k1 k2 p1 p2]. See https://www.mrpt.org/Camera_Parameters
See also
undistort_point

Definition at line 133 of file pinhole.cpp.

References ASSERT_, mrpt::img::TCamera::dist, and mrpt::img::TCamera::intrinsicParams.

◆ undistort_points() [2/2]

void mrpt::vision::pinhole::undistort_points ( const std::vector< mrpt::img::TPixelCoordf > &  srcDistortedPixels,
std::vector< mrpt::img::TPixelCoordf > &  dstUndistortedPixels,
const mrpt::img::TCamera cameraModel 
)

Undistort a list of points given by their pixel coordinates, provided the camera matrix and distortion coefficients.

Parameters
srcDistortedPixels[IN] The pixel coordinates as in the distorted image.
dstUndistortedPixels[OUT] The computed pixel coordinates without distortion.
cameraModel[IN] The camera parameters.
See also
undistort_point

Definition at line 145 of file pinhole.cpp.

References mrpt::img::TCamera::cx(), mrpt::img::TCamera::cy(), mrpt::d2f(), mrpt::img::TCamera::dist, mrpt::img::TCamera::fx(), mrpt::img::TCamera::fy(), MRPT_END, and MRPT_START.

Here is the call graph for this function:



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020