Visual Servoing Platform
version 3.0.1
|
#include <visp3/vision/vpKeyPoint.h>
Public Member Functions | |
vpKeyPoint (const vpFeatureDetectorType &detectorType, const vpFeatureDescriptorType &descriptorType, const std::string &matcherName, const vpFilterMatchingType &filterType=ratioDistanceThreshold) | |
vpKeyPoint (const std::string &detectorName="ORB", const std::string &extractorName="ORB", const std::string &matcherName="BruteForce-Hamming", const vpFilterMatchingType &filterType=ratioDistanceThreshold) | |
vpKeyPoint (const std::vector< std::string > &detectorNames, const std::vector< std::string > &extractorNames, const std::string &matcherName="BruteForce", const vpFilterMatchingType &filterType=ratioDistanceThreshold) | |
unsigned int | buildReference (const vpImage< unsigned char > &I) |
unsigned int | buildReference (const vpImage< unsigned char > &I, const vpImagePoint &iP, const unsigned int height, const unsigned int width) |
unsigned int | buildReference (const vpImage< unsigned char > &I, const vpRect &rectangle) |
void | buildReference (const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &trainKeyPoint, std::vector< cv::Point3f > &points3f, const bool append=false, const int class_id=-1) |
void | buildReference (const vpImage< unsigned char > &I, const std::vector< cv::KeyPoint > &trainKeyPoint, const cv::Mat &trainDescriptors, const std::vector< cv::Point3f > &points3f, const bool append=false, const int class_id=-1) |
bool | computePose (const std::vector< cv::Point2f > &imagePoints, const std::vector< cv::Point3f > &objectPoints, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, std::vector< int > &inlierIndex, double &elapsedTime, bool(*func)(vpHomogeneousMatrix *)=NULL) |
bool | computePose (const std::vector< vpPoint > &objectVpPoints, vpHomogeneousMatrix &cMo, std::vector< vpPoint > &inliers, double &elapsedTime, bool(*func)(vpHomogeneousMatrix *)=NULL) |
bool | computePose (const std::vector< vpPoint > &objectVpPoints, vpHomogeneousMatrix &cMo, std::vector< vpPoint > &inliers, std::vector< unsigned int > &inlierIndex, double &elapsedTime, bool(*func)(vpHomogeneousMatrix *)=NULL) |
void | createImageMatching (vpImage< unsigned char > &IRef, vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching) |
void | createImageMatching (vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching) |
void | detect (const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, const vpRect &rectangle=vpRect()) |
void | detect (const cv::Mat &matImg, std::vector< cv::KeyPoint > &keyPoints, const cv::Mat &mask=cv::Mat()) |
void | detect (const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, double &elapsedTime, const vpRect &rectangle=vpRect()) |
void | detect (const cv::Mat &matImg, std::vector< cv::KeyPoint > &keyPoints, double &elapsedTime, const cv::Mat &mask=cv::Mat()) |
void | detectExtractAffine (const vpImage< unsigned char > &I, std::vector< std::vector< cv::KeyPoint > > &listOfKeypoints, std::vector< cv::Mat > &listOfDescriptors, std::vector< vpImage< unsigned char > > *listOfAffineI=NULL) |
void | display (const vpImage< unsigned char > &IRef, const vpImage< unsigned char > &ICurrent, unsigned int size=3) |
void | display (const vpImage< unsigned char > &ICurrent, unsigned int size=3, const vpColor &color=vpColor::green) |
void | displayMatching (const vpImage< unsigned char > &IRef, vpImage< unsigned char > &IMatching, unsigned int crossSize, unsigned int lineThickness=1, const vpColor &color=vpColor::green) |
void | displayMatching (const vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching, const std::vector< vpImagePoint > &ransacInliers=std::vector< vpImagePoint >(), unsigned int crossSize=3, unsigned int lineThickness=1) |
void | extract (const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, cv::Mat &descriptors, std::vector< cv::Point3f > *trainPoints=NULL) |
void | extract (const cv::Mat &matImg, std::vector< cv::KeyPoint > &keyPoints, cv::Mat &descriptors, std::vector< cv::Point3f > *trainPoints=NULL) |
void | extract (const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, cv::Mat &descriptors, double &elapsedTime, std::vector< cv::Point3f > *trainPoints=NULL) |
void | extract (const cv::Mat &matImg, std::vector< cv::KeyPoint > &keyPoints, cv::Mat &descriptors, double &elapsedTime, std::vector< cv::Point3f > *trainPoints=NULL) |
vpMatrix | getCovarianceMatrix () const |
double | getDetectionTime () const |
cv::Ptr< cv::FeatureDetector > | getDetector (const vpFeatureDetectorType &type) const |
cv::Ptr< cv::FeatureDetector > | getDetector (const std::string &name) const |
std::map < vpFeatureDetectorType, std::string > | getDetectorNames () const |
double | getExtractionTime () const |
cv::Ptr< cv::DescriptorExtractor > | getExtractor (const vpFeatureDescriptorType &type) const |
cv::Ptr< cv::DescriptorExtractor > | getExtractor (const std::string &name) const |
std::map < vpFeatureDescriptorType, std::string > | getExtractorNames () const |
vpImageFormatType | getImageFormat () const |
double | getMatchingTime () const |
cv::Ptr< cv::DescriptorMatcher > | getMatcher () const |
std::vector< cv::DMatch > | getMatches () const |
std::vector< std::pair < cv::KeyPoint, cv::KeyPoint > > | getMatchQueryToTrainKeyPoints () const |
unsigned int | getNbImages () const |
void | getObjectPoints (std::vector< cv::Point3f > &objectPoints) const |
void | getObjectPoints (std::vector< vpPoint > &objectPoints) const |
double | getPoseTime () const |
cv::Mat | getQueryDescriptors () const |
void | getQueryKeyPoints (std::vector< cv::KeyPoint > &keyPoints) const |
void | getQueryKeyPoints (std::vector< vpImagePoint > &keyPoints) const |
std::vector< vpImagePoint > | getRansacInliers () const |
std::vector< vpImagePoint > | getRansacOutliers () const |
cv::Mat | getTrainDescriptors () const |
void | getTrainKeyPoints (std::vector< cv::KeyPoint > &keyPoints) const |
void | getTrainKeyPoints (std::vector< vpImagePoint > &keyPoints) const |
void | getTrainPoints (std::vector< cv::Point3f > &points) const |
void | getTrainPoints (std::vector< vpPoint > &points) const |
void | initMatcher (const std::string &matcherName) |
void | insertImageMatching (const vpImage< unsigned char > &IRef, const vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching) |
void | insertImageMatching (const vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching) |
void | loadConfigFile (const std::string &configFile) |
void | loadLearningData (const std::string &filename, const bool binaryMode=false, const bool append=false) |
void | match (const cv::Mat &trainDescriptors, const cv::Mat &queryDescriptors, std::vector< cv::DMatch > &matches, double &elapsedTime) |
unsigned int | matchPoint (const vpImage< unsigned char > &I) |
unsigned int | matchPoint (const vpImage< unsigned char > &I, const vpImagePoint &iP, const unsigned int height, const unsigned int width) |
unsigned int | matchPoint (const vpImage< unsigned char > &I, const vpRect &rectangle) |
bool | matchPoint (const vpImage< unsigned char > &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL, const vpRect &rectangle=vpRect()) |
bool | matchPoint (const vpImage< unsigned char > &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, double &error, double &elapsedTime, bool(*func)(vpHomogeneousMatrix *)=NULL, const vpRect &rectangle=vpRect()) |
bool | matchPointAndDetect (const vpImage< unsigned char > &I, vpRect &boundingBox, vpImagePoint ¢erOfGravity, const bool isPlanarObject=true, std::vector< vpImagePoint > *imPts1=NULL, std::vector< vpImagePoint > *imPts2=NULL, double *meanDescriptorDistance=NULL, double *detectionScore=NULL, const vpRect &rectangle=vpRect()) |
bool | matchPointAndDetect (const vpImage< unsigned char > &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, double &error, double &elapsedTime, vpRect &boundingBox, vpImagePoint ¢erOfGravity, bool(*func)(vpHomogeneousMatrix *)=NULL, const vpRect &rectangle=vpRect()) |
void | reset () |
void | saveLearningData (const std::string &filename, const bool binaryMode=false, const bool saveTrainingImages=true) |
void | setCovarianceComputation (const bool &flag) |
void | setDetectionMethod (const vpDetectionMethodType &method) |
void | setDetector (const vpFeatureDetectorType &detectorType) |
void | setDetector (const std::string &detectorName) |
template<typename T1 , typename T2 , typename T3 > | |
void | setDetectorParameter (const T1 detectorName, const T2 parameterName, const T3 value) |
void | setDetectors (const std::vector< std::string > &detectorNames) |
void | setExtractor (const vpFeatureDescriptorType &extractorType) |
void | setExtractor (const std::string &extractorName) |
template<typename T1 , typename T2 , typename T3 > | |
void | setExtractorParameter (const T1 extractorName, const T2 parameterName, const T3 value) |
void | setExtractors (const std::vector< std::string > &extractorNames) |
void | setImageFormat (const vpImageFormatType &imageFormat) |
void | setMatcher (const std::string &matcherName) |
void | setFilterMatchingType (const vpFilterMatchingType &filterType) |
void | setMatchingFactorThreshold (const double factor) |
void | setMatchingRatioThreshold (const double ratio) |
void | setRansacConsensusPercentage (const double percentage) |
void | setRansacIteration (const int nbIter) |
void | setRansacReprojectionError (const double reprojectionError) |
void | setRansacMinInlierCount (const int minCount) |
void | setRansacThreshold (const double threshold) |
void | setUseAffineDetection (const bool useAffine) |
void | setUseBruteForceCrossCheck (const bool useCrossCheck) |
void | setUseMatchTrainToQuery (const bool useMatchTrainToQuery) |
void | setUseRansacConsensusPercentage (const bool usePercentage) |
void | setUseRansacVVS (const bool ransacVVS) |
void | setUseSingleMatchFilter (const bool singleMatchFilter) |
bool | referenceBuilt () const |
const vpImagePoint * | getAllPointsInReferenceImage () |
void | getReferencePoint (const unsigned int index, vpImagePoint &referencePoint) |
void | getMatchedPoints (const unsigned int index, vpImagePoint &referencePoint, vpImagePoint ¤tPoint) |
unsigned int | getIndexInAllReferencePointList (const unsigned int indexInMatchedPointList) |
unsigned int | getReferencePointNumber () const |
unsigned int | getMatchedPointNumber () const |
const std::vector< vpImagePoint > & | getReferenceImagePointsList () const |
const std::vector< vpImagePoint > & | getCurrentImagePointsList () const |
const std::vector< unsigned int > & | getMatchedReferencePoints () const |
Static Public Member Functions | |
static void | compute3D (const cv::KeyPoint &candidate, const std::vector< vpPoint > &roi, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, cv::Point3f &point) |
static void | compute3D (const vpImagePoint &candidate, const std::vector< vpPoint > &roi, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, vpPoint &point) |
static void | compute3DForPointsInPolygons (const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpPolygon > &polygons, const std::vector< std::vector< vpPoint > > &roisPt, std::vector< cv::Point3f > &points, cv::Mat *descriptors=NULL) |
static void | compute3DForPointsInPolygons (const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< vpImagePoint > &candidates, const std::vector< vpPolygon > &polygons, const std::vector< std::vector< vpPoint > > &roisPt, std::vector< vpPoint > &points, cv::Mat *descriptors=NULL) |
static void | compute3DForPointsOnCylinders (const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpCylinder > &cylinders, const std::vector< std::vector< std::vector< vpImagePoint > > > &vectorOfCylinderRois, std::vector< cv::Point3f > &points, cv::Mat *descriptors=NULL) |
static void | compute3DForPointsOnCylinders (const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< vpImagePoint > &candidates, const std::vector< vpCylinder > &cylinders, const std::vector< std::vector< std::vector< vpImagePoint > > > &vectorOfCylinderRois, std::vector< vpPoint > &points, cv::Mat *descriptors=NULL) |
Protected Attributes | |
std::vector< vpImagePoint > | referenceImagePointsList |
std::vector< vpImagePoint > | currentImagePointsList |
std::vector< unsigned int > | matchedReferencePoints |
bool | _reference_computed |
Class that allows keypoints detection (and descriptors extraction) and matching thanks to OpenCV library. Thus to enable this class OpenCV should be installed. Installation instructions are provided here https://visp.inria.fr/3rd_opencv.
This class permits to use different types of detectors, extractors and matchers easily. So, the classical SIFT and SURF keypoints could be used, as well as ORB, FAST, (etc.) keypoints, depending of the version of OpenCV you use.
The goal of this class is to provide a tool to match reference keypoints from a reference image (or train keypoints in OpenCV terminology) and detected keypoints from a current image (or query keypoints in OpenCV terminology).
If you supply the corresponding 3D coordinates corresponding to the 2D coordinates of the reference keypoints, you can also estimate the pose of the object by matching a set of detected keypoints in the current image with the reference keypoints.
If you use this class, the first thing you have to do is to build the reference keypoints by detecting keypoints in a reference image which contains the object to detect. Then you match keypoints detected in a current image with those detected in a reference image by calling matchPoint() methods. You can access to the lists of matched points thanks to the methods getMatchedPointsInReferenceImage() and getMatchedPointsInCurrentImage(). These two methods return a list of matched points. The nth element of the first list is matched with the nth element of the second list. To provide easy compatibility with OpenCV terminology, getTrainKeyPoints() give you access to the list of keypoints detected in train images (or reference images) and getQueryKeyPoints() give you access to the list of keypoints detected in a query image (or current image). The method getMatches() give you access to a list of cv::DMatch with the correspondence between the index of the train keypoints and the index of the query keypoints.
The following small example shows how to use the class to do the matching between current and reference keypoints.
It is also possible to build the reference keypoints in a region of interest (ROI) of an image and find keypoints to match in only a part of the current image. The small following example shows how to do this:
This class is also described in Tutorial: Keypoints matching.
Definition at line 217 of file vpKeyPoint.h.
Predefined detection method identifier.
Definition at line 231 of file vpKeyPoint.h.
Predefined constant for descriptor extraction type.
Enumerator | |
---|---|
DESCRIPTOR_ORB | |
DESCRIPTOR_BRISK | |
DESCRIPTOR_FREAK | |
DESCRIPTOR_BRIEF | |
DESCRIPTOR_SIFT | |
DESCRIPTOR_SURF | |
DESCRIPTOR_TYPE_SIZE |
Definition at line 274 of file vpKeyPoint.h.
Predefined constant for feature detection type.
Enumerator | |
---|---|
DETECTOR_FAST | |
DETECTOR_MSER | |
DETECTOR_ORB | |
DETECTOR_BRISK | |
DETECTOR_GFTT | |
DETECTOR_SimpleBlob | |
DETECTOR_STAR | |
DETECTOR_SIFT | |
DETECTOR_SURF | |
DETECTOR_TYPE_SIZE |
Definition at line 246 of file vpKeyPoint.h.
Predefined filtering method identifier.
Definition at line 222 of file vpKeyPoint.h.
Predefined constant for training image format.
Definition at line 238 of file vpKeyPoint.h.
vpKeyPoint::vpKeyPoint | ( | const vpFeatureDetectorType & | detectorType, |
const vpFeatureDescriptorType & | descriptorType, | ||
const std::string & | matcherName, | ||
const vpFilterMatchingType & | filterType = ratioDistanceThreshold |
||
) |
Constructor to initialize the specified detector, descriptor, matcher and filtering method.
detectorType | : Type of feature detector. |
descriptorType | : Type of the descriptor extractor. |
matcherName | : Name of the matcher. |
filterType | : Filtering matching method chosen. |
Definition at line 334 of file vpKeyPoint.cpp.
vpKeyPoint::vpKeyPoint | ( | const std::string & | detectorName = "ORB" , |
const std::string & | extractorName = "ORB" , |
||
const std::string & | matcherName = "BruteForce-Hamming" , |
||
const vpFilterMatchingType & | filterType = ratioDistanceThreshold |
||
) |
Constructor to initialize the specified detector, descriptor, matcher and filtering method.
detectorName | : Name of the detector. |
extractorName | : Name of the extractor. |
matcherName | : Name of the matcher. |
filterType | : Filtering matching method chosen. |
Definition at line 369 of file vpKeyPoint.cpp.
vpKeyPoint::vpKeyPoint | ( | const std::vector< std::string > & | detectorNames, |
const std::vector< std::string > & | extractorNames, | ||
const std::string & | matcherName = "BruteForce" , |
||
const vpFilterMatchingType & | filterType = ratioDistanceThreshold |
||
) |
Constructor to initialize specified detector, extractor, matcher and filtering method.
detectorNames | : List of name detector for allowing multiple detectors. |
extractorNames | : List of name extractor for allowing multiple extractors. |
matcherName | : Name of the matcher. |
filterType | : Filtering matching method chosen. |
Definition at line 404 of file vpKeyPoint.cpp.
|
virtual |
Build the reference keypoints list.
I | : Input reference image. |
I
. Implements vpBasicKeyPoint.
Definition at line 490 of file vpKeyPoint.cpp.
Referenced by buildReference().
|
virtual |
Build the reference keypoints list in a region of interest in the image.
I | : Input reference image |
iP | : Position of the top-left corner of the region of interest. |
height | : Height of the region of interest. |
width | : Width of the region of interest. |
Implements vpBasicKeyPoint.
Definition at line 503 of file vpKeyPoint.cpp.
References buildReference().
|
virtual |
Build the reference keypoints list in a region of interest in the image.
I | : Input image. |
rectangle | : Rectangle of the region of interest. |
Implements vpBasicKeyPoint.
Definition at line 517 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, vpConvert::convertFromOpenCV(), detect(), detectExtractAffine(), extract(), and vpBasicKeyPoint::referenceImagePointsList.
void vpKeyPoint::buildReference | ( | const vpImage< unsigned char > & | I, |
std::vector< cv::KeyPoint > & | trainKeyPoints, | ||
std::vector< cv::Point3f > & | points3f, | ||
const bool | append = false , |
||
const int | class_id = -1 |
||
) |
Build the reference keypoints list and compute the 3D position corresponding of the keypoints locations.
I | : Input image |
trainKeyPoints | : List of the train keypoints. |
points3f | : Output list of the 3D position corresponding of the keypoints locations. |
append | : If true, append the supply train keypoints with those already present. |
class_id | : The class id to be set to the input cv::KeyPoint if != -1. |
Definition at line 584 of file vpKeyPoint.cpp.
References buildReference(), and extract().
void vpKeyPoint::buildReference | ( | const vpImage< unsigned char > & | I, |
const std::vector< cv::KeyPoint > & | trainKeyPoints, | ||
const cv::Mat & | trainDescriptors, | ||
const std::vector< cv::Point3f > & | points3f, | ||
const bool | append = false , |
||
const int | class_id = -1 |
||
) |
Build the reference keypoints list and compute the 3D position corresponding of the keypoints locations.
I | : Input image |
trainKeyPoints | : List of the train keypoints. |
points3f | : List of the 3D position corresponding of the keypoints locations. |
trainDescriptors | : List of the train descriptors. |
append | : If true, append the supply train keypoints with those already present. |
class_id | : The class id to be set to the input cv::KeyPoint if != -1. |
Definition at line 625 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, vpConvert::convertFromOpenCV(), and vpBasicKeyPoint::referenceImagePointsList.
|
static |
Compute the 3D coordinate in the world/object frame given the 2D image coordinate and under the assumption that the point is located on a plane whose the plane equation is known in the camera frame. The Z-coordinate is retrieved according to the proportional relationship between the plane equation expressed in the normalized camera frame (derived from the image coordinate) and the same plane equation expressed in the camera frame.
candidate | : Keypoint we want to compute the 3D coordinate. |
roi | : List of 3D points in the camera frame representing a planar face. |
cam | : Camera parameters. |
cMo | : Homogeneous matrix between the world and the camera frames. |
point | : 3D coordinate in the world/object frame computed. |
Definition at line 688 of file vpKeyPoint.cpp.
References vpPixelMeterConversion::convertPoint(), vpPlane::getA(), vpPlane::getB(), vpPlane::getC(), vpPlane::getD(), and vpHomogeneousMatrix::inverse().
Referenced by compute3DForPointsInPolygons().
|
static |
Compute the 3D coordinate in the world/object frame given the 2D image coordinate and under the assumption that the point is located on a plane whose the plane equation is known in the camera frame. The Z-coordinate is retrieved according to the proportional relationship between the plane equation expressed in the normalized camera frame (derived from the image coordinate) and the same plane equation expressed in the camera frame.
candidate | : vpImagePoint we want to compute the 3D coordinate. |
roi | : List of 3D points in the camera frame representing a planar face. |
cam | : Camera parameters. |
cMo | : Homogeneous matrix between the world and the camera frames. |
point | : 3D coordinate in the world/object frame computed. |
Definition at line 726 of file vpKeyPoint.cpp.
References vpPixelMeterConversion::convertPoint(), vpPlane::getA(), vpPlane::getB(), vpPlane::getC(), vpPlane::getD(), vpHomogeneousMatrix::inverse(), and vpPoint::setWorldCoordinates().
|
static |
Keep only keypoints located on faces and compute for those keypoints the 3D coordinate in the world/object frame given the 2D image coordinate and under the assumption that the point is located on a plane.
cMo | : Homogeneous matrix between the world and the camera frames. |
cam | : Camera parameters. |
candidates | : In input, list of keypoints detected in the whole image, in output, list of keypoints only located on planes. |
polygons | : List of 2D polygons representing the projection of the faces in the image plane. |
roisPt | : List of faces, with the 3D coordinates known in the camera frame. |
points | : Output list of computed 3D coordinates (in the world/object frame) of keypoints located only on faces. |
descriptors | : Optional parameter, pointer to the descriptors to filter. |
Definition at line 765 of file vpKeyPoint.cpp.
References compute3D(), and vpImagePoint::set_ij().
|
static |
Keep only keypoints located on faces and compute for those keypoints the 3D coordinate in the world/object frame given the 2D image coordinate and under the assumption that the point is located on a plane.
cMo | : Homogeneous matrix between the world and the camera frames. |
cam | : Camera parameters. |
candidates | : In input, list of vpImagePoint located in the whole image, in output, list of vpImagePoint only located on planes. |
polygons | : List of 2D polygons representing the projection of the faces in the image plane. |
roisPt | : List of faces, with the 3D coordinates known in the camera frame. |
points | : Output list of computed 3D coordinates (in the world/object frame) of vpImagePoint located only on faces. |
descriptors | : Optional parameter, pointer to the descriptors to filter |
Definition at line 823 of file vpKeyPoint.cpp.
References compute3D().
|
static |
Keep only keypoints located on cylinders and compute the 3D coordinates in the world/object frame given the 2D image coordinates.
cMo | : Homogeneous matrix between the world and the camera frames. |
cam | : Camera parameters. |
candidates | : In input, list of keypoints detected in the whole image, in output, list of keypoints only located on cylinders. |
cylinders | : List of vpCylinder corresponding of the cylinder objects in the scene, projected in the camera frame. |
vectorOfCylinderRois | : For each cylinder, the corresponding list of bounding box. |
points | : Output list of computed 3D coordinates in the world/object frame for each keypoint located on a cylinder. |
descriptors | : Optional parameter, pointer to the descriptors to filter. |
Definition at line 874 of file vpKeyPoint.cpp.
References vpPixelMeterConversion::convertPoint(), vpPoint::get_oX(), vpPoint::get_oY(), vpPoint::get_oZ(), vpHomogeneousMatrix::inverse(), vpPolygon::isInside(), vpMath::isNaN(), and vpPoint::setWorldCoordinates().
|
static |
Keep only vpImagePoint located on cylinders and compute the 3D coordinates in the world/object frame given the 2D image coordinates.
cMo | : Homogeneous matrix between the world and the camera frames. |
cam | : Camera parameters. |
candidates | : In input, list of vpImagePoint located in the image, in output, list of vpImagePoint only located on cylinders. |
cylinders | : List of vpCylinder corresponding of the cylinder objects in the scene, projected in the camera frame. |
vectorOfCylinderRois | : For each cylinder, the corresponding list of bounding box. |
points | : Output list of computed 3D coordinates in the world/object frame for each vpImagePoint located on a cylinder. |
descriptors | : Optional parameter, pointer to the descriptors to filter. |
Definition at line 942 of file vpKeyPoint.cpp.
References vpPixelMeterConversion::convertPoint(), vpHomogeneousMatrix::inverse(), vpPolygon::isInside(), vpMath::isNaN(), and vpPoint::setWorldCoordinates().
bool vpKeyPoint::computePose | ( | const std::vector< cv::Point2f > & | imagePoints, |
const std::vector< cv::Point3f > & | objectPoints, | ||
const vpCameraParameters & | cam, | ||
vpHomogeneousMatrix & | cMo, | ||
std::vector< int > & | inlierIndex, | ||
double & | elapsedTime, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL |
||
) |
Compute the pose using the correspondence between 2D points and 3D points using OpenCV function with RANSAC method.
imagePoints | : List of 2D points corresponding to the location of the detected keypoints. |
objectPoints | : List of the 3D points in the object frame matched. |
cam | : Camera parameters. |
cMo | : Homogeneous matrix between the object frame and the camera frame. |
inlierIndex | : List of indexes of inliers. |
elapsedTime | : Elapsed time. |
func | : Function pointer to filter the final pose returned by OpenCV pose estimation method. |
Definition at line 1010 of file vpKeyPoint.cpp.
References vpCameraParameters::get_px(), vpCameraParameters::get_py(), vpCameraParameters::get_u0(), vpCameraParameters::get_v0(), and vpTime::measureTimeMs().
Referenced by computePose(), and matchPoint().
bool vpKeyPoint::computePose | ( | const std::vector< vpPoint > & | objectVpPoints, |
vpHomogeneousMatrix & | cMo, | ||
std::vector< vpPoint > & | inliers, | ||
double & | elapsedTime, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL |
||
) |
Compute the pose using the correspondence between 2D points and 3D points using ViSP function with RANSAC method.
objectVpPoints | : List of vpPoint with coordinates expressed in the object and in the camera frame. |
cMo | : Homogeneous matrix between the object frame and the camera frame. |
inliers | : List of inliers. |
elapsedTime | : Elapsed time. |
func | : Function pointer to filter the pose in Ransac pose estimation, if we want to eliminate the poses which do not respect some criterion |
Definition at line 1101 of file vpKeyPoint.cpp.
References computePose().
bool vpKeyPoint::computePose | ( | const std::vector< vpPoint > & | objectVpPoints, |
vpHomogeneousMatrix & | cMo, | ||
std::vector< vpPoint > & | inliers, | ||
std::vector< unsigned int > & | inlierIndex, | ||
double & | elapsedTime, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL |
||
) |
Compute the pose using the correspondence between 2D points and 3D points using ViSP function with RANSAC method.
objectVpPoints | : List of vpPoint with coordinates expressed in the object and in the camera frame. |
cMo | : Homogeneous matrix between the object frame and the camera frame. |
inliers | : List of inlier points. |
inlierIndex | : List of inlier index. |
elapsedTime | : Elapsed time. |
func | : Function pointer to filter the pose in Ransac pose estimation, if we want to eliminate the poses which do not respect some criterion |
Definition at line 1119 of file vpKeyPoint.cpp.
References vpPose::addPoint(), vpPose::computePose(), vpPose::getCovarianceMatrix(), vpPose::getRansacInlierIndex(), vpPose::getRansacInliers(), vpTime::measureTimeMs(), vpPose::RANSAC, vpPose::setCovarianceComputation(), vpPose::setRansacMaxTrials(), vpPose::setRansacNbInliersToReachConsensus(), vpPose::setRansacThreshold(), and vpException::what().
void vpKeyPoint::createImageMatching | ( | vpImage< unsigned char > & | IRef, |
vpImage< unsigned char > & | ICurrent, | ||
vpImage< unsigned char > & | IMatching | ||
) |
Initialize the size of the matching image (case with a matching side by side between IRef and ICurrent).
IRef | : Reference image. |
ICurrent | : Current image. |
IMatching | : Image matching. |
Definition at line 1219 of file vpKeyPoint.cpp.
References vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().
Referenced by createImageMatching().
void vpKeyPoint::createImageMatching | ( | vpImage< unsigned char > & | ICurrent, |
vpImage< unsigned char > & | IMatching | ||
) |
Initialize the size of the matching image with appropriate size according to the number of training images. Used to display the matching of keypoints detected in the current image with those detected in multiple training images.
ICurrent | : Current image. |
IMatching | : Image initialized with appropriate size. |
Definition at line 1236 of file vpKeyPoint.cpp.
References createImageMatching(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpMath::round().
void vpKeyPoint::detect | ( | const vpImage< unsigned char > & | I, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
const vpRect & | rectangle = vpRect() |
||
) |
Detect keypoints in the image.
I | : Input image. |
keyPoints | : Output list of the detected keypoints. |
rectangle | : Optional rectangle of the region of interest. |
Definition at line 1286 of file vpKeyPoint.cpp.
Referenced by buildReference(), detect(), and matchPoint().
void vpKeyPoint::detect | ( | const cv::Mat & | matImg, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
const cv::Mat & | mask = cv::Mat() |
||
) |
Detect keypoints in the image.
matImg | : Input image. |
keyPoints | : Output list of the detected keypoints. |
mask | : Optional 8-bit integer mask to detect only where mask[i][j] != 0. |
Definition at line 1298 of file vpKeyPoint.cpp.
References detect().
void vpKeyPoint::detect | ( | const vpImage< unsigned char > & | I, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
double & | elapsedTime, | ||
const vpRect & | rectangle = vpRect() |
||
) |
Detect keypoints in the image.
I | : Input image. |
keyPoints | : Output list of the detected keypoints. |
elapsedTime | : Elapsed time. |
rectangle | : Optional rectangle of the region of interest. |
Definition at line 1311 of file vpKeyPoint.cpp.
References vpImageConvert::convert(), detect(), vpRect::getBottom(), vpRect::getHeight(), vpRect::getLeft(), vpRect::getRight(), vpRect::getTop(), and vpRect::getWidth().
void vpKeyPoint::detect | ( | const cv::Mat & | matImg, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
double & | elapsedTime, | ||
const cv::Mat & | mask = cv::Mat() |
||
) |
Detect keypoints in the image.
matImg | : Input image. |
keyPoints | : Output list of the detected keypoints. |
elapsedTime | : Elapsed time. |
mask | : Optional 8-bit integer mask to detect only where mask[i][j] != 0. |
Definition at line 1336 of file vpKeyPoint.cpp.
References vpTime::measureTimeMs().
void vpKeyPoint::detectExtractAffine | ( | const vpImage< unsigned char > & | I, |
std::vector< std::vector< cv::KeyPoint > > & | listOfKeypoints, | ||
std::vector< cv::Mat > & | listOfDescriptors, | ||
std::vector< vpImage< unsigned char > > * | listOfAffineI = NULL |
||
) |
Apply a set of affine transormations to the image, detect keypoints and reproject them into initial image coordinates. See http://www.ipol.im/pub/algo/my_affine_sift/ for the details. See https://github.com/Itseez/opencv/blob/master/samples/python2/asift.py for the Python implementation by Itseez and Matt Sheckells for the current implementation in C++.
I | : Input image |
listOfKeypoints | : List of detected keypoints in the multiple images after affine transformations |
listOfDescriptors | : Corresponding list of descriptors |
listOfAffineI | : Optional parameter, list of images after affine transformations |
Definition at line 3562 of file vpKeyPoint.cpp.
References vpImageConvert::convert(), and extract().
Referenced by buildReference(), and matchPoint().
|
virtual |
Display the reference and the detected keypoints in the images.
IRef | : Input reference image. |
ICurrent | : Input current image. |
size | : Size of the displayed cross. |
Implements vpBasicKeyPoint.
Definition at line 1357 of file vpKeyPoint.cpp.
References vpDisplay::displayCross(), getQueryKeyPoints(), getTrainKeyPoints(), vpColor::green, and vpColor::red.
|
virtual |
Display the reference keypoints.
ICurrent | : Input current image. |
size | : Size of the displayed crosses. |
color | : Color of the crosses. |
Implements vpBasicKeyPoint.
Definition at line 1377 of file vpKeyPoint.cpp.
References vpDisplay::displayCross(), and getQueryKeyPoints().
void vpKeyPoint::displayMatching | ( | const vpImage< unsigned char > & | IRef, |
vpImage< unsigned char > & | IMatching, | ||
unsigned int | crossSize, | ||
unsigned int | lineThickness = 1 , |
||
const vpColor & | color = vpColor::green |
||
) |
Display the matching lines between the detected keypoints with those detected in one training image.
IRef | : Reference image, used to have the x-offset. |
IMatching | : Resulting image matching. |
crossSize | : Size of the displayed crosses. |
lineThickness | : Thickness of the displayed lines. |
color | : Color to use, if none, we pick randomly a color for each pair of matching. |
Definition at line 1395 of file vpKeyPoint.cpp.
References vpDisplay::displayCross(), vpDisplay::displayLine(), getQueryKeyPoints(), getTrainKeyPoints(), vpImage< Type >::getWidth(), and vpColor::none.
Referenced by displayMatching().
void vpKeyPoint::displayMatching | ( | const vpImage< unsigned char > & | ICurrent, |
vpImage< unsigned char > & | IMatching, | ||
const std::vector< vpImagePoint > & | ransacInliers = std::vector<vpImagePoint>() , |
||
unsigned int | crossSize = 3 , |
||
unsigned int | lineThickness = 1 |
||
) |
Display matching between keypoints detected in the current image and with those detected in the multiple training images. Display also RANSAC inliers if the list is supplied.
ICurrent | : Current image. |
IMatching | : Resulting matching image. |
ransacInliers | : List of Ransac inliers or empty list if not available. |
crossSize | : Size of the displayed crosses. |
lineThickness | : Thickness of the displayed line. |
Definition at line 1431 of file vpKeyPoint.cpp.
References vpDisplay::displayCircle(), vpDisplay::displayCross(), vpDisplay::displayLine(), displayMatching(), vpImagePoint::get_i(), vpImagePoint::get_j(), vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpColor::green, vpColor::red, vpMath::round(), and vpImagePoint::set_ij().
void vpKeyPoint::extract | ( | const vpImage< unsigned char > & | I, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
cv::Mat & | descriptors, | ||
std::vector< cv::Point3f > * | trainPoints = NULL |
||
) |
Extract the descriptors for each keypoints of the list.
I | : Input image. |
keyPoints | : List of keypoints we want to extract their descriptors. |
descriptors | : Descriptors matrix with at each row the descriptors values for each keypoint. |
trainPoints | : Pointer to the list of 3D train points, when a keypoint cannot be extracted, we need to remove the corresponding 3D point. |
Definition at line 1544 of file vpKeyPoint.cpp.
Referenced by buildReference(), detectExtractAffine(), extract(), and matchPoint().
void vpKeyPoint::extract | ( | const cv::Mat & | matImg, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
cv::Mat & | descriptors, | ||
std::vector< cv::Point3f > * | trainPoints = NULL |
||
) |
Extract the descriptors for each keypoints of the list.
matImg | : Input image. |
keyPoints | : List of keypoints we want to extract their descriptors. |
descriptors | : Descriptors matrix with at each row the descriptors values for each keypoint. |
trainPoints | : Pointer to the list of 3D train points, when a keypoint cannot be extracted, we need to remove the corresponding 3D point. |
Definition at line 1559 of file vpKeyPoint.cpp.
References extract().
void vpKeyPoint::extract | ( | const vpImage< unsigned char > & | I, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
cv::Mat & | descriptors, | ||
double & | elapsedTime, | ||
std::vector< cv::Point3f > * | trainPoints = NULL |
||
) |
Extract the descriptors for each keypoints of the list.
I | : Input image. |
keyPoints | : List of keypoints we want to extract their descriptors. |
descriptors | : Descriptors matrix with at each row the descriptors values for each keypoint. |
elapsedTime | : Elapsed time. |
trainPoints | : Pointer to the list of 3D train points, when a keypoint cannot be extracted, we need to remove the corresponding 3D point. |
Definition at line 1575 of file vpKeyPoint.cpp.
References vpImageConvert::convert(), and extract().
void vpKeyPoint::extract | ( | const cv::Mat & | matImg, |
std::vector< cv::KeyPoint > & | keyPoints, | ||
cv::Mat & | descriptors, | ||
double & | elapsedTime, | ||
std::vector< cv::Point3f > * | trainPoints = NULL |
||
) |
Extract the descriptors for each keypoints of the list.
matImg | : Input image. |
keyPoints | : List of keypoints we want to extract their descriptors. |
descriptors | : Descriptors matrix with at each row the descriptors values for each keypoint. |
elapsedTime | : Elapsed time. |
trainPoints | : Pointer to the list of 3D train points, when a keypoint cannot be extracted, we need to remove the corresponding 3D point. |
Definition at line 1592 of file vpKeyPoint.cpp.
References vpTime::measureTimeMs().
|
inlineinherited |
Get the pointer to the complete list of reference points. The pointer is const. Thus the points can not be modified
Definition at line 110 of file vpBasicKeyPoint.h.
|
inline |
Get the covariance matrix when estimating the pose using the Virtual Visual Servoing approach.
Definition at line 394 of file vpKeyPoint.h.
|
inlineinherited |
Return the vector of current image point.
Definition at line 207 of file vpBasicKeyPoint.h.
|
inline |
Get the elapsed time to compute the keypoint detection.
Definition at line 415 of file vpKeyPoint.h.
|
inline |
Get the detector pointer.
type | : Type of the detector. |
Definition at line 425 of file vpKeyPoint.h.
|
inline |
Get the detector pointer.
name | : Name of the detector. |
Definition at line 446 of file vpKeyPoint.h.
|
inline |
Get the feature detector name associated to the type.
Definition at line 459 of file vpKeyPoint.h.
|
inline |
Get the elapsed time to compute the keypoint extraction.
Definition at line 468 of file vpKeyPoint.h.
|
inline |
Get the extractor pointer.
type | : Type of the descriptor extractor. |
Definition at line 478 of file vpKeyPoint.h.
|
inline |
Get the extractor pointer.
name | : Name of the descriptor extractor. |
Definition at line 499 of file vpKeyPoint.h.
|
inline |
Get the feature descriptor extractor name associated to the type.
Definition at line 512 of file vpKeyPoint.h.
|
inline |
Get the image format to use when saving training images.
Definition at line 521 of file vpKeyPoint.h.
|
inlineinherited |
Get the nth matched reference point index in the complete list of reference point.
In the code below referencePoint1 and referencePoint2 correspond to the same matched reference point.
Definition at line 168 of file vpBasicKeyPoint.h.
References vpException::fatalError, and vpTRACE.
|
inlineinherited |
Get the number of matched points.
Definition at line 189 of file vpBasicKeyPoint.h.
|
inlineinherited |
Get the nth couple of reference point and current point which have been matched. These points are copied in the vpImagePoint instances given in argument.
index | : The index of the desired couple of reference point and current point . The index must be between 0 and the number of matched points - 1. |
referencePoint | : The coordinates of the desired reference point are copied here. |
currentPoint | : The coordinates of the desired current point are copied here. |
Definition at line 138 of file vpBasicKeyPoint.h.
References vpException::fatalError, vpImagePoint::set_ij(), and vpTRACE.
|
inlineinherited |
Return the index of the matched associated to the current image point i. The ith element of the vector is the index of the reference image point matching with the current image point.
Definition at line 218 of file vpBasicKeyPoint.h.
|
inline |
|
inline |
Get the list of matches (correspondences between the indexes of the detected keypoints and the train keypoints).
Definition at line 548 of file vpKeyPoint.h.
|
inline |
Get the elapsed time to compute the matching.
Definition at line 530 of file vpKeyPoint.h.
|
inline |
Get the list of pairs with the correspondence between the matched query and train keypoints.
Definition at line 557 of file vpKeyPoint.h.
|
inline |
Get the number of train images.
Definition at line 572 of file vpKeyPoint.h.
void vpKeyPoint::getObjectPoints | ( | std::vector< cv::Point3f > & | objectPoints | ) | const |
Get the 3D coordinates of the object points matched (the corresponding 3D coordinates in the object frame of the keypoints detected in the current image after the matching).
objectPoints | : List of 3D coordinates in the object frame. |
Definition at line 1820 of file vpKeyPoint.cpp.
void vpKeyPoint::getObjectPoints | ( | std::vector< vpPoint > & | objectPoints | ) | const |
Get the 3D coordinates of the object points matched (the corresponding 3D coordinates in the object frame of the keypoints detected in the current image after the matching).
objectPoints | : List of 3D coordinates in the object frame. |
Definition at line 1830 of file vpKeyPoint.cpp.
References vpConvert::convertFromOpenCV().
|
inline |
Get the elapsed time to compute the pose.
Definition at line 584 of file vpKeyPoint.h.
|
inline |
Get the descriptors matrix for the query keypoints.
Definition at line 593 of file vpKeyPoint.h.
void vpKeyPoint::getQueryKeyPoints | ( | std::vector< cv::KeyPoint > & | keyPoints | ) | const |
Get the query keypoints list in OpenCV type.
keyPoints | : List of query keypoints (or keypoints detected in the current image). |
Definition at line 1839 of file vpKeyPoint.cpp.
Referenced by display(), and displayMatching().
void vpKeyPoint::getQueryKeyPoints | ( | std::vector< vpImagePoint > & | keyPoints | ) | const |
Get the query keypoints list in ViSP type.
keyPoints | : List of query keypoints (or keypoints detected in the current image). |
Definition at line 1848 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::currentImagePointsList.
|
inline |
Get the list of Ransac inliers.
Definition at line 605 of file vpKeyPoint.h.
|
inline |
Get the list of Ransac outliers.
Definition at line 614 of file vpKeyPoint.h.
|
inlineinherited |
Return the vector of reference image point.
Definition at line 198 of file vpBasicKeyPoint.h.
|
inlineinherited |
Get the nth reference point. This point is copied in the vpImagePoint instance given in argument.
index | : The index of the desired reference point. The index must be between 0 and the number of reference points - 1. |
referencePoint | : The coordinates of the desired reference point are copied there. |
Definition at line 120 of file vpBasicKeyPoint.h.
References vpException::fatalError, vpImagePoint::set_ij(), and vpTRACE.
|
inlineinherited |
Get the number of reference points.
Definition at line 182 of file vpBasicKeyPoint.h.
|
inline |
Get the train descriptors matrix.
Definition at line 623 of file vpKeyPoint.h.
void vpKeyPoint::getTrainKeyPoints | ( | std::vector< cv::KeyPoint > & | keyPoints | ) | const |
Get the train keypoints list in OpenCV type.
keyPoints | : List of train keypoints (or reference keypoints). |
Definition at line 1857 of file vpKeyPoint.cpp.
Referenced by display(), and displayMatching().
void vpKeyPoint::getTrainKeyPoints | ( | std::vector< vpImagePoint > & | keyPoints | ) | const |
Get the train keypoints list in ViSP type.
keyPoints | : List of train keypoints (or reference keypoints). |
Definition at line 1866 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::referenceImagePointsList.
void vpKeyPoint::getTrainPoints | ( | std::vector< cv::Point3f > & | points | ) | const |
Get the train points (the 3D coordinates in the object frame) list in OpenCV type.
points | : List of train points (or reference points). |
Definition at line 1875 of file vpKeyPoint.cpp.
void vpKeyPoint::getTrainPoints | ( | std::vector< vpPoint > & | points | ) | const |
Get the train points (the 3D coordinates in the object frame) list in ViSP type.
points | : List of train points (or reference points). |
Definition at line 1884 of file vpKeyPoint.cpp.
void vpKeyPoint::initMatcher | ( | const std::string & | matcherName | ) |
Initialize a matcher based on its name.
matcherName | : Name of the matcher (e.g BruteForce, FlannBased). |
Definition at line 2320 of file vpKeyPoint.cpp.
References vpException::fatalError.
void vpKeyPoint::insertImageMatching | ( | const vpImage< unsigned char > & | IRef, |
const vpImage< unsigned char > & | ICurrent, | ||
vpImage< unsigned char > & | IMatching | ||
) |
Insert a reference image and a current image side-by-side.
IRef | : Reference image. |
ICurrent | : Current image. |
IMatching | : Matching image for displaying all the matching between the query keypoints and those detected in the training images. |
Definition at line 2380 of file vpKeyPoint.cpp.
References vpImage< Type >::getWidth(), and vpImage< Type >::insert().
Referenced by insertImageMatching().
void vpKeyPoint::insertImageMatching | ( | const vpImage< unsigned char > & | ICurrent, |
vpImage< unsigned char > & | IMatching | ||
) |
Insert the different training images in the matching image.
ICurrent | : Current image. |
IMatching | : Matching image for displaying all the matching between the query keypoints and those detected in the training images |
Definition at line 2395 of file vpKeyPoint.cpp.
References vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpImage< Type >::insert(), insertImageMatching(), and vpMath::round().
void vpKeyPoint::loadConfigFile | ( | const std::string & | configFile | ) |
Load configuration parameters from an XML config file.
configFile | : Path to the XML config file. |
Definition at line 2458 of file vpKeyPoint.cpp.
References vpXmlConfigParserKeyPoint::constantFactorDistanceThreshold, constantFactorDistanceThreshold, vpXmlConfigParserKeyPoint::getDetectorName(), vpXmlConfigParserKeyPoint::getExtractorName(), vpXmlConfigParserKeyPoint::getMatcherName(), vpXmlConfigParserKeyPoint::getMatchingFactorThreshold(), vpXmlConfigParserKeyPoint::getMatchingMethod(), vpXmlConfigParserKeyPoint::getMatchingRatioThreshold(), vpXmlConfigParserKeyPoint::getNbRansacIterations(), vpXmlConfigParserKeyPoint::getNbRansacMinInlierCount(), vpXmlConfigParserKeyPoint::getRansacConsensusPercentage(), vpXmlConfigParserKeyPoint::getRansacReprojectionError(), vpXmlConfigParserKeyPoint::getRansacThreshold(), vpXmlConfigParserKeyPoint::getUseRansacConsensusPercentage(), vpXmlConfigParserKeyPoint::getUseRansacVVSPoseEstimation(), vpException::ioError, vpXmlConfigParserKeyPoint::noFilterMatching, noFilterMatching, vpXmlConfigParserKeyPoint::parse(), vpXmlConfigParserKeyPoint::ratioDistanceThreshold, ratioDistanceThreshold, vpXmlConfigParserKeyPoint::stdAndRatioDistanceThreshold, stdAndRatioDistanceThreshold, vpXmlConfigParserKeyPoint::stdDistanceThreshold, and stdDistanceThreshold.
void vpKeyPoint::loadLearningData | ( | const std::string & | filename, |
const bool | binaryMode = false , |
||
const bool | append = false |
||
) |
Load learning data saved on disk.
filename | : Path of the learning file. |
binaryMode | : If true, the learning file is in a binary mode, otherwise it is in XML mode. |
append | : If true, concatenate the learning data, otherwise reset the variables. |
Definition at line 2532 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, vpConvert::convertFromOpenCV(), vpIoTools::getParent(), vpException::ioError, vpIoTools::isAbsolutePathname(), vpImageIo::read(), and vpBasicKeyPoint::referenceImagePointsList.
void vpKeyPoint::match | ( | const cv::Mat & | trainDescriptors, |
const cv::Mat & | queryDescriptors, | ||
std::vector< cv::DMatch > & | matches, | ||
double & | elapsedTime | ||
) |
Match keypoints based on distance between their descriptors.
trainDescriptors | : Train descriptors (or reference descriptors). |
queryDescriptors | : Query descriptors. |
matches | : Output list of matches. |
elapsedTime | : Elapsed time. |
Definition at line 3000 of file vpKeyPoint.cpp.
References vpTime::measureTimeMs().
Referenced by matchPoint().
|
virtual |
Match keypoints detected in the image with those built in the reference list.
I | : Input current image. |
Implements vpBasicKeyPoint.
Definition at line 3056 of file vpKeyPoint.cpp.
Referenced by matchPoint(), and matchPointAndDetect().
|
virtual |
Match keypoints detected in a region of interest of the image with those built in the reference list.
I | : Input image |
iP | : Coordinate of the top-left corner of the region of interest |
height | : Height of the region of interest |
width | : Width of the region of interest |
Implements vpBasicKeyPoint.
Definition at line 3070 of file vpKeyPoint.cpp.
References matchPoint().
|
virtual |
Match keypoints detected in a region of interest of the image with those built in the reference list.
I | : Input image |
rectangle | : Rectangle of the region of interest |
Implements vpBasicKeyPoint.
Definition at line 3084 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, vpConvert::convertFromOpenCV(), vpBasicKeyPoint::currentImagePointsList, detect(), detectExtractAffine(), extract(), match(), vpBasicKeyPoint::matchedReferencePoints, and noFilterMatching.
bool vpKeyPoint::matchPoint | ( | const vpImage< unsigned char > & | I, |
const vpCameraParameters & | cam, | ||
vpHomogeneousMatrix & | cMo, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL , |
||
const vpRect & | rectangle = vpRect() |
||
) |
Match keypoints detected in the image with those built in the reference list and compute the pose.
I | : Input image |
cam | : Camera parameters |
cMo | : Homogeneous matrix between the object frame and the camera frame |
func | : Function pointer to filter the pose in Ransac pose estimation, if we want to eliminate the poses which do not respect some criterion |
rectangle | : Rectangle corresponding to the ROI (Region of Interest) to consider |
Definition at line 3175 of file vpKeyPoint.cpp.
References matchPoint().
bool vpKeyPoint::matchPoint | ( | const vpImage< unsigned char > & | I, |
const vpCameraParameters & | cam, | ||
vpHomogeneousMatrix & | cMo, | ||
double & | error, | ||
double & | elapsedTime, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL , |
||
const vpRect & | rectangle = vpRect() |
||
) |
Match keypoints detected in the image with those built in the reference list and compute the pose.
I | : Input image |
cam | : Camera parameters |
cMo | : Homogeneous matrix between the object frame and the camera frame |
error | : Reprojection mean square error (in pixel) between the 2D points and the projection of the 3D points with the estimated pose |
elapsedTime | : Time to detect, extract, match and compute the pose |
func | : Function pointer to filter the pose in Ransac pose estimation, if we want to eliminate the poses which do not respect some criterion |
rectangle | : Rectangle corresponding to the ROI (Region of Interest) to consider |
Definition at line 3195 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, computePose(), vpConvert::convertFromOpenCV(), vpPixelMeterConversion::convertPoint(), vpBasicKeyPoint::currentImagePointsList, detect(), detectExtractAffine(), extract(), match(), vpBasicKeyPoint::matchedReferencePoints, noFilterMatching, vpPoint::set_x(), vpPoint::set_y(), and vpPoint::setWorldCoordinates().
bool vpKeyPoint::matchPointAndDetect | ( | const vpImage< unsigned char > & | I, |
vpRect & | boundingBox, | ||
vpImagePoint & | centerOfGravity, | ||
const bool | isPlanarObject = true , |
||
std::vector< vpImagePoint > * | imPts1 = NULL , |
||
std::vector< vpImagePoint > * | imPts2 = NULL , |
||
double * | meanDescriptorDistance = NULL , |
||
double * | detection_score = NULL , |
||
const vpRect & | rectangle = vpRect() |
||
) |
Match keypoints detected in the image with those built in the reference list and return the bounding box and the center of gravity.
I | : Input image |
boundingBox | : Bounding box that contains the good matches |
centerOfGravity | : Center of gravity computed from the location of the good matches (could differ of the center of the bounding box) |
isPlanarObject | : If the object is planar, the homography matrix is estimated to eliminate outliers, otherwise it is the fundamental matrix which is estimated |
imPts1 | : Pointer to the list of reference keypoints if not null |
imPts2 | : Pointer to the list of current keypoints if not null |
meanDescriptorDistance | : Pointer to the value of the average distance of the descriptors if not null |
detection_score | : Pointer to the value of the detection score if not null |
rectangle | : Rectangle corresponding to the ROI (Region of Interest) to consider |
Definition at line 3378 of file vpKeyPoint.cpp.
References detectionThreshold, vpPolygon::getBoundingBox(), matchPoint(), vpImagePoint::set_u(), and vpImagePoint::set_v().
bool vpKeyPoint::matchPointAndDetect | ( | const vpImage< unsigned char > & | I, |
const vpCameraParameters & | cam, | ||
vpHomogeneousMatrix & | cMo, | ||
double & | error, | ||
double & | elapsedTime, | ||
vpRect & | boundingBox, | ||
vpImagePoint & | centerOfGravity, | ||
bool(*)(vpHomogeneousMatrix *) | func = NULL , |
||
const vpRect & | rectangle = vpRect() |
||
) |
Match keypoints detected in the image with those built in the reference list, compute the pose and return also the bounding box and the center of gravity.
I | : Input image |
cam | : Camera parameters |
cMo | : Homogeneous matrix between the object frame and the camera frame |
error | : Reprojection mean square error (in pixel) between the 2D points and the projection of the 3D points with the estimated pose |
elapsedTime | : Time to detect, extract, match and compute the pose |
boundingBox | : Bounding box that contains the good matches |
centerOfGravity | : Center of gravity computed from the location of the good matches (could differ of the center of the bounding box) |
func | : Function pointer to filter the pose in Ransac pose estimation, if we want to eliminate the poses which do not respect some criterion |
rectangle | : Rectangle corresponding to the ROI (Region of Interest) to consider |
Definition at line 3512 of file vpKeyPoint.cpp.
References vpMeterPixelConversion::convertPoint(), vpPoint::get_x(), vpPoint::get_y(), vpPolygon::getBoundingBox(), matchPoint(), vpForwardProjection::project(), vpImagePoint::set_u(), and vpImagePoint::set_v().
|
inlineinherited |
Indicate wether the reference has been built or not.
Definition at line 103 of file vpBasicKeyPoint.h.
void vpKeyPoint::reset | ( | ) |
Reset the instance as if we would declare another vpKeyPoint variable.
Definition at line 3694 of file vpKeyPoint.cpp.
References vpBasicKeyPoint::_reference_computed, vpBasicKeyPoint::currentImagePointsList, detectionScore, jpgImageFormat, vpBasicKeyPoint::matchedReferencePoints, ratioDistanceThreshold, and vpBasicKeyPoint::referenceImagePointsList.
void vpKeyPoint::saveLearningData | ( | const std::string & | filename, |
const bool | binaryMode = false , |
||
const bool | saveTrainingImages = true |
||
) |
Save the learning data in a file in XML or binary mode.
filename | : Path of the save file |
binaryMode | : If true, the data are saved in binary mode, otherwise in XML mode |
saveTrainingImages | : If true, save also the training images on disk |
Definition at line 3732 of file vpKeyPoint.cpp.
References vpException::fatalError, vpIoTools::getParent(), vpException::ioError, jpgImageFormat, vpIoTools::makeDirectory(), pgmImageFormat, pngImageFormat, ppmImageFormat, and vpImageIo::write().
|
inline |
Set if the covariance matrix has to be computed in the Virtual Visual Servoing approach.
flag | : True if the covariance has to be computed, false otherwise. |
Definition at line 677 of file vpKeyPoint.h.
|
inline |
Set the method to decide if the object is present or not.
method | : Detection method (detectionThreshold or detectionScore). |
Definition at line 691 of file vpKeyPoint.h.
|
inline |
Set and initialize a detector.
detectorType | : Type of the detector. |
Definition at line 700 of file vpKeyPoint.h.
|
inline |
Set and initialize a detector denominated by his name detectorName
.
detectorName | : Name of the detector. |
Definition at line 712 of file vpKeyPoint.h.
|
inline |
Template function to set to a parameterName
a value for a specific detector named by his detectorName
.
detectorName | : Name of the detector |
parameterName | : Name of the parameter |
value | : Value to set |
Definition at line 727 of file vpKeyPoint.h.
|
inline |
Set and initialize a list of detectors denominated by their names detectorNames
.
detectorNames | : List of detector names. |
Definition at line 740 of file vpKeyPoint.h.
|
inline |
Set and initialize a descriptor extractor.
extractorType | : Type of the descriptor extractor. |
Definition at line 752 of file vpKeyPoint.h.
|
inline |
Set and initialize a descriptor extractor denominated by his name extractorName
.
extractorName | : Name of the extractor. |
Definition at line 764 of file vpKeyPoint.h.
|
inline |
Template function to set to a parameterName
a value for a specific extractor named by his extractorName
.
extractorName | : Name of the extractor |
parameterName | : Name of the parameter |
value | : Value to set |
Definition at line 779 of file vpKeyPoint.h.
|
inline |
Set and initialize a list of extractors denominated by their names extractorNames
.
extractorNames | : List of extractor names. |
Definition at line 792 of file vpKeyPoint.h.
|
inline |
Set the filtering method to eliminate false matching. The different methods are:
filterType | : Type of the filtering method |
Definition at line 838 of file vpKeyPoint.h.
|
inline |
Set the image format to use when saving training images.
imageFormat | : The image format. |
Definition at line 804 of file vpKeyPoint.h.
|
inline |
Set and initialize a matcher denominated by his name matcherName
. The different matchers are:
L1 and L2 norms are preferable choices for SIFT and SURF descriptors, NORM_HAMMING should be used with ORB, BRISK and BRIEF, NORM_HAMMING2 should be used with ORB when WTA_K==3 or 4.
matcherName | : Name of the matcher. |
Definition at line 822 of file vpKeyPoint.h.
|
inline |
Set the factor value for the filtering method: constantFactorDistanceThreshold.
factor | : Factor value |
Definition at line 870 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the ratio value for the filtering method: ratioDistanceThreshold.
ratio | : Ratio value (]0 ; 1]) |
Definition at line 883 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the percentage value for defining the cardinality of the consensus group.
percentage | : Percentage value (]0 ; 100]) |
Definition at line 896 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the maximum number of iterations for the Ransac pose estimation method.
nbIter | : Maximum number of iterations for the Ransac |
Definition at line 909 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the minimum number of inlier for the Ransac pose estimation method.
minCount | : Minimum number of inlier for the consensus |
Definition at line 935 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the maximum reprojection error (in pixel) to determine if a point is an inlier or not.
reprojectionError | : Maximum reprojection error in pixel (used by OpenCV function) |
Definition at line 922 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set the maximum error (in meter) to determine if a point is an inlier or not.
threshold | : Maximum error in meter for ViSP function |
Definition at line 948 of file vpKeyPoint.h.
References vpException::badValue.
|
inline |
Set if multiple affine transformations must be used to detect and extract keypoints.
useAffine | : True to use multiple affine transformations, false otherwise |
Definition at line 961 of file vpKeyPoint.h.
|
inline |
Set if cross check method must be used to eliminate some false matches with a brute-force matching method.
useCrossCheck | : True to use cross check, false otherwise |
Definition at line 971 of file vpKeyPoint.h.
|
inline |
Set if we want to match the train keypoints to the query keypoints.
useMatchTrainToQuery | : True to match the train keypoints to the query keypoints |
Definition at line 987 of file vpKeyPoint.h.
|
inline |
Set the flag to choose between a percentage value of inliers for the cardinality of the consensus group or a minimum number.
usePercentage | : True to a percentage ratio of inliers, otherwise use a specified number of inliers |
Definition at line 997 of file vpKeyPoint.h.
|
inline |
Set the flag to choose between the OpenCV or ViSP Ransac pose estimation function.
ransacVVS | : True to use ViSP function, otherwise use OpenCV function |
Definition at line 1006 of file vpKeyPoint.h.
|
inline |
Set the flag to filter matches where multiple query keypoints are matched to the same train keypoints.
singleMatchFilter | : True to use the single match filter. |
Definition at line 1015 of file vpKeyPoint.h.
|
protectedinherited |
flag to indicate if the reference has been built.
Definition at line 244 of file vpBasicKeyPoint.h.
Referenced by vpKeyPointSurf::buildReference(), vpFernClassifier::buildReference(), buildReference(), loadLearningData(), matchPoint(), and reset().
|
protectedinherited |
List of the points which belong to the current image and have been matched with points belonging to the reference.
Definition at line 233 of file vpBasicKeyPoint.h.
Referenced by vpKeyPointSurf::display(), vpFernClassifier::display(), getQueryKeyPoints(), vpKeyPointSurf::matchPoint(), vpFernClassifier::matchPoint(), matchPoint(), and reset().
|
protectedinherited |
Array containing the index in the array "referenceImagePointsList" of the reference points which have been matched.
The first element of the "currentImagePointsList" array is matched with the nth element of the "referenceImagePointsList" array. The value of n is stored in the first element of the "matchedReferencePoints" array.
Definition at line 241 of file vpBasicKeyPoint.h.
Referenced by vpKeyPointSurf::display(), vpFernClassifier::display(), vpKeyPointSurf::matchPoint(), vpFernClassifier::matchPoint(), matchPoint(), and reset().
|
protectedinherited |
List of the points which define the reference.
Definition at line 227 of file vpBasicKeyPoint.h.
Referenced by vpKeyPointSurf::buildReference(), buildReference(), vpKeyPointSurf::display(), vpFernClassifier::display(), vpKeyPointSurf::getDescriptorParamReferencePoint(), vpKeyPointSurf::getDescriptorReferencePoint(), vpKeyPointSurf::getLaplacianReferencePoint(), getTrainKeyPoints(), loadLearningData(), reset(), and vpFernClassifier::train().