[mrpt-vision]
Computer vision algorithms
Library mrpt-vision
This library is part of MRPT and can be installed in Debian-based systems with:
sudo apt install libmrpt-vision-dev
Read also how to import MRPT into your CMake scripts.
This library includes some extensions to OpenCV functionality, plus some original classes:
The namespace mrpt::vision::pinhole contains several projection and Jacobian auxiliary functions for projective cameras.
Sparse Bundle Adjustment algorithms. See [mrpt-vision-lgpl]
A versatile feature tracker. See mrpt::vision::CGenericFeatureTracker and the implementation mrpt::vision::CFeatureTracker_KL
mrpt::vision::CFeature : A generic representation of a visual feature, with or without patch, with or without a set of descriptors.
mrpt::vision::CFeatureExtraction : A hub for a number of detection algorithms and different descriptors.
mrpt::vision::TSIFTDescriptorsKDTreeIndex, mrpt::vision::find_descriptor_pairings() and others: KD-tree-based SIFT/SURF feature matching.
mrpt::vision::CVideoFileWriter : A class to write video files.
mrpt::vision::CUndistortMap : A cache of the map for undistorting image, very efficient for sequences of images all with the same distortion parameters.
This library defines a new type of observation (mrpt::obs::CObservationVisualLandmarks) and a new type of map (mrpt::maps::CLandmarksMap).
Notice that sets of parameters for monocular and stereo cameras are defined in grp_mrpt_img for convenience, in the classes:
mrpt::vision::CDifodo : A class which implements a Visual Odometry algorithm based on depth images and the “range flow constraint equation”.
See all the classes in mrpt::vision
Library contents
// typedefs typedef uint64_t mrpt::vision::TFeatureID; typedef uint64_t mrpt::vision::TLandmarkID; typedef uint64_t mrpt::vision::TCameraPoseID; typedef std::map<TCameraPoseID, mrpt::poses::CPose3D> mrpt::vision::TFramePosesMap; typedef std::vector<mrpt::poses::CPose3D> mrpt::vision::TFramePosesVec; typedef std::map<TLandmarkID, mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsMap; typedef std::vector<mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsVec; typedef std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos> mrpt::vision::TRelativeFeaturePosMap; // enums enum mrpt::vision::TDescriptorType; enum mrpt::vision::TFeatureTrackStatus; enum mrpt::vision::TKeyPointMethod; // structs struct mrpt::vision::TFeatureObservation; struct mrpt::vision::TImageROI; struct mrpt::vision::TMatchingOptions; struct mrpt::vision::TMultiResDescMatchOptions; struct mrpt::vision::TMultiResDescOptions; struct mrpt::vision::TMultiResMatchingOutput; struct mrpt::vision::TROI; struct mrpt::vision::TRelativeFeaturePos; struct mrpt::vision::TSequenceFeatureObservations; struct mrpt::vision::TStereoSystemParams; // classes class mrpt::vision::CDifodo; class mrpt::vision::CFeatureLines; class mrpt::vision::CImagePyramid; class mrpt::maps::CLandmark; class mrpt::maps::CLandmarksMap; class mrpt::obs::CObservationVisualLandmarks; class mrpt::vision::CStereoRectifyMap; class mrpt::vision::CUndistortMap; class mrpt::vision::CVideoFileWriter; // global functions void mrpt::vision::registerAllClasses_mrpt_vision(); 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 ); mrpt::math::TPoint3D mrpt::vision::pixelTo3D(const mrpt::img::TPixelCoordf& xy, const mrpt::math::CMatrixDouble33& A); mrpt::math::CMatrixDouble33 mrpt::vision::buildIntrinsicParamsMatrix( const double focalLengthX, const double focalLengthY, const double centerX, const double centerY ); double mrpt::vision::computeMsd(const mrpt::tfest::TMatchingPairList& list, const poses::CPose3D& Rt); void mrpt::vision::cloudsToMatchedList(const mrpt::obs::CObservationVisualLandmarks& cloud1, const mrpt::obs::CObservationVisualLandmarks& cloud2, mrpt::tfest::TMatchingPairList& outList); float mrpt::vision::computeMainOrientation(const mrpt::img::CImage& image, unsigned int x, unsigned int y); void mrpt::vision::normalizeImage(const mrpt::img::CImage& image, mrpt::img::CImage& nimage); size_t mrpt::vision::matchFeatures( const CFeatureList& list1, const CFeatureList& list2, CMatchedFeatureList& matches, const TMatchingOptions& options = TMatchingOptions(), const TStereoSystemParams& params = TStereoSystemParams() ); void mrpt::vision::generateMask(const CMatchedFeatureList& mList, mrpt::math::CMatrixBool& mask1, mrpt::math::CMatrixBool& mask2, int wSize = 10); double mrpt::vision::computeSAD(const mrpt::img::CImage& patch1, const mrpt::img::CImage& patch2); void mrpt::vision::addFeaturesToImage(const mrpt::img::CImage& inImg, const CFeatureList& theList, mrpt::img::CImage& outImg); 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() ); void mrpt::vision::projectMatchedFeature(const CFeature& leftFeat, const CFeature& rightFeat, mrpt::math::TPoint3D& p3D, const TStereoSystemParams& params = TStereoSystemParams()); void mrpt::vision::projectMatchedFeatures(CMatchedFeatureList& mfList, const TStereoSystemParams& param, mrpt::maps::CLandmarksMap& landmarks); void mrpt::vision::projectMatchedFeatures(CFeatureList& leftList, CFeatureList& rightList, const TStereoSystemParams& param, mrpt::maps::CLandmarksMap& landmarks); void mrpt::vision::StereoObs2BRObs(const mrpt::obs::CObservationStereoImages& inObs, const std::vector<double>& sg, mrpt::obs::CObservationBearingRange& outObs); 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 ); void mrpt::vision::StereoObs2BRObs(const mrpt::obs::CObservationVisualLandmarks& inObs, mrpt::obs::CObservationBearingRange& outObs); 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 ); 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 ); 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); 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 ); 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 ); 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 ); void mrpt::vision::pinhole::undistort_points( const std::vector<mrpt::img::TPixelCoordf>& srcDistortedPixels, std::vector<mrpt::img::TPixelCoordf>& dstUndistortedPixels, const mrpt::img::TCamera& cameraModel ); void mrpt::vision::pinhole::undistort_point(const mrpt::img::TPixelCoordf& inPt, mrpt::img::TPixelCoordf& outPt, const mrpt::img::TCamera& cameraModel);
Typedefs
typedef uint64_t mrpt::vision::TFeatureID
Definition of a feature ID.
typedef uint64_t mrpt::vision::TLandmarkID
Unique IDs for landmarks.
typedef uint64_t mrpt::vision::TCameraPoseID
Unique IDs for camera frames (poses)
typedef std::map<TCameraPoseID, mrpt::poses::CPose3D> mrpt::vision::TFramePosesMap
A list of camera frames (6D poses) indexed by unique IDs.
typedef std::vector<mrpt::poses::CPose3D> mrpt::vision::TFramePosesVec
A list of camera frames (6D poses), which assumes indexes are unique, consecutive IDs.
typedef std::map<TLandmarkID, mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsMap
A list of landmarks (3D points) indexed by unique IDs.
typedef std::vector<mrpt::math::TPoint3D> mrpt::vision::TLandmarkLocationsVec
A list of landmarks (3D points), which assumes indexes are unique, consecutive IDs.
typedef std::map<mrpt::vision::TFeatureID, TRelativeFeaturePos> mrpt::vision::TRelativeFeaturePosMap
An index of feature IDs and their relative locations.
Global Functions
void mrpt::vision::registerAllClasses_mrpt_vision()
Forces manual RTTI registration of all serializable classes in this namespace.
Should never be required to be explicitly called by users, except if building MRPT as a static library.
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
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.
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, TPixelCoordf
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:
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.
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 |
See also:
double mrpt::vision::computeMsd(const mrpt::tfest::TMatchingPairList& list, const poses::CPose3D& Rt)
Computes the mean squared distance between a set of 3D correspondences …
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 …
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.
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. |
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.
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. |
if |
mList.size() = 0 |
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]
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. |
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. |
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. |
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
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
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).
Fields of view are not computed.
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). |
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. |
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). |
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. |
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
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)
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.
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. |
See also:
projectPoints_with_distortion, projectPoint_no_distortion
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.
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\)
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 )
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
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)
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.
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. |
See also:
projectPoint_with_distortion, projectPoints_no_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)
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.
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. |
See also:
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.
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:
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:
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: