Main class for marker detection. More...
#include <markerdetector_impl.h>
Classes | |
struct | marker_analyzer |
class | Queue |
struct | ThresAndDetectRectTASK |
Public Types | |
typedef Marker | MarkerCandidate |
Public Member Functions | |
std::vector< aruco::Marker > | detect (const cv::Mat &input) |
std::vector< aruco::Marker > | detect (const cv::Mat &input, const CameraParameters &camParams, float markerSizeMeters, bool setYPerperdicular=false, bool correctFisheye=false) |
void | detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerperdicular=false, bool correctFisheye=false) |
void | detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), cv::Mat extrinsics=cv::Mat(), float markerSizeMeters=-1, bool setYPerperdicular=false, bool correctFisheye=false) |
void | fromStream (std::istream &str) |
std::vector< MarkerCandidate > | getCandidates () const |
DetectionMode | getDetectionMode () |
std::vector< cv::Mat > | getImagePyramid () |
cv::Ptr< MarkerLabeler > | getMarkerLabeler () |
MarkerDetector::Params & | getParameters () |
MarkerDetector::Params | getParameters () const |
cv::Mat | getThresholdedImage (uint32_t idx=0) |
void | loadParamsFromFile (const std::string &path) |
MarkerDetector_Impl () | |
MarkerDetector_Impl (int dict_type, float error_correction_rate=0) | |
MarkerDetector_Impl (std::string dict_type, float error_correction_rate=0) | |
void | saveParamsToFile (const std::string &path) const |
void | setDetectionMode (DetectionMode dm, float minMarkerSize=0) |
void | setDictionary (int dict_type, float error_correction_rate=0) |
setDictionary Specifies the dictionary you want to use for marker decoding More... | |
void | setDictionary (std::string dict_type, float error_correction_rate=0) |
void | setMarkerLabeler (cv::Ptr< MarkerLabeler > detector) |
setMakerLabeler sets the labeler employed to analyze the squares and extract the inner binary code More... | |
void | setParameters (const MarkerDetector::Params ¶ms) |
void | toStream (std::ostream &str) const |
bool | warp (cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points) |
~MarkerDetector_Impl () | |
Private Types | |
enum | ThreadTasks { THRESHOLD_TASK, ENCLOSE_TASK, EXIT_TASK } |
Private Member Functions | |
void | addToImageHist (cv::Mat &im, std::vector< float > &hist) |
void | buildPyramid (std::vector< cv::Mat > &imagePyramid, const cv::Mat &grey, int minSize) |
void | cornerUpsample (std::vector< Marker > &MarkerCanditates, cv::Size lowResImageSize) |
void | cornerUpsample (std::vector< std::vector< cv::Point2f >> &MarkerCanditates, cv::Size lowResImageSize) |
void | distortPoints (std::vector< cv::Point2f > in, std::vector< cv::Point2f > &out, const cv::Mat &camMatrix, const cv::Mat &distCoeff) |
void | draw (cv::Mat out, const std::vector< Marker > &markers) |
void | drawAllContours (cv::Mat input, std::vector< std::vector< cv::Point >> &contours) |
void | drawApproxCurve (cv::Mat &in, std::vector< cv::Point > &approxCurve, cv::Scalar color, int thickness=1) |
void | drawContour (cv::Mat &in, std::vector< cv::Point > &contour, cv::Scalar) |
void | enlargeMarkerCandidate (MarkerCandidate &cand, int fact=1) |
void | filter_ambiguous_query (std::vector< cv::DMatch > &matches) |
cv::Point2f | getCrossPoint (const cv::Point3f &line1, const cv::Point3f &line2) |
int | getMarkerWarpSize () |
int | getMinMarkerSizePix (cv::Size orginput_imageSize) const |
void | interpolate2Dline (const std::vector< cv::Point2f > &inPoints, cv::Point3f &outLine) |
template<typename T > | |
void | joinVectors (std::vector< std::vector< T >> &vv, std::vector< T > &v, bool clearv=false) |
int | Otsu (std::vector< float > &hist) |
int | perimeter (const std::vector< cv::Point2f > &a) |
float | pointSqdist (cv::Point &p, cv::Point2f &p2) |
std::vector< aruco::MarkerCandidate > | prefilterCandidates (std::vector< MarkerCandidate > &candidates, cv::Size orgImageSize) |
void | refineCornerWithContourLines (aruco::Marker &marker, cv::Mat cameraMatrix=cv::Mat(), cv::Mat distCoef=cv::Mat()) |
template<typename T > | |
void | removeElements (std::vector< T > &vinout, const std::vector< bool > &toRemove) |
std::vector< aruco::MarkerCandidate > | thresholdAndDetectRectangles (const cv::Mat &image) |
std::vector< aruco::MarkerCandidate > | thresholdAndDetectRectangles (const cv::Mat &input, int thres_param1, int thres_param2, bool erode, cv::Mat &auxThresImage) |
void | thresholdAndDetectRectangles_thread () |
Private Attributes | |
std::vector< MarkerCandidate > | _candidates_wcontour |
MarkerDetector::Params | _params |
std::vector< Marker > | _prevMarkers |
Queue< ThresAndDetectRectTASK > | _tasks |
std::vector< cv::Mat > | _thres_Images |
float | _tooNearDistance = -1 |
std::vector< std::vector< MarkerCandidate > > | _vcandidates |
cv::Mat | grey |
std::vector< cv::Mat > | imagePyramid |
std::map< int, int > | marker_ndetections |
cv::Ptr< MarkerLabeler > | markerIdDetector |
cv::Mat | thres |
Friends | |
class | MarkerDetector |
Main class for marker detection.
Definition at line 41 of file markerdetector_impl.h.
Definition at line 229 of file markerdetector_impl.h.
|
private |
Enumerator | |
---|---|
THRESHOLD_TASK | |
ENCLOSE_TASK | |
EXIT_TASK |
Definition at line 361 of file markerdetector_impl.h.
aruco::MarkerDetector_Impl::MarkerDetector_Impl | ( | ) |
See
Definition at line 49 of file markerdetector_impl.cpp.
aruco::MarkerDetector_Impl::MarkerDetector_Impl | ( | int | dict_type, |
float | error_correction_rate = 0 |
||
) |
Creates indicating the dictionary. See
dict_type | Dictionary employed. See |
error_correction_rate | value indicating the correction error allowed. Is in range [0,1]. 0 means no correction at all. So an erroneous bit will result in discarding the marker. 1, mean full correction. The maximum number of bits that can be corrected depends on each ditionary. We recommend using values from 0 to 0.5. (in general, this will allow up to 3 bits or correction). |
Definition at line 60 of file markerdetector_impl.cpp.
aruco::MarkerDetector_Impl::MarkerDetector_Impl | ( | std::string | dict_type, |
float | error_correction_rate = 0 |
||
) |
Definition at line 71 of file markerdetector_impl.cpp.
aruco::MarkerDetector_Impl::~MarkerDetector_Impl | ( | ) |
Definition at line 83 of file markerdetector_impl.cpp.
|
private |
Definition at line 729 of file markerdetector_impl.cpp.
|
private |
Definition at line 174 of file markerdetector_impl.cpp.
|
private |
Definition at line 1789 of file markerdetector_impl.cpp.
|
private |
Definition at line 1837 of file markerdetector_impl.cpp.
std::vector< aruco::Marker > aruco::MarkerDetector_Impl::detect | ( | const cv::Mat & | input | ) |
Detects the markers in the image passed
If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected
input | input color image |
camMatrix | intrinsic camera information. |
distCoeff | camera distorsion coefficient. If set Mat() if is assumed no camera distorion |
markerSizeMeters | size of the marker sides expressed in meters. If not specified this value, the extrinsics of the markers are not detected. |
setYPerperdicular | If set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis |
correctFisheye | Correct fisheye distortion |
Definition at line 118 of file markerdetector_impl.cpp.
std::vector< aruco::Marker > aruco::MarkerDetector_Impl::detect | ( | const cv::Mat & | input, |
const CameraParameters & | camParams, | ||
float | markerSizeMeters, | ||
bool | setYPerperdicular = false , |
||
bool | correctFisheye = false |
||
) |
Definition at line 125 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::detect | ( | const cv::Mat & | input, |
std::vector< Marker > & | detectedMarkers, | ||
CameraParameters | camParams, | ||
float | markerSizeMeters = -1 , |
||
bool | setYPerperdicular = false , |
||
bool | correctFisheye = false |
||
) |
Detects the markers in the image passed
If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected
input | input color image |
detectedMarkers | output vector with the markers detected |
camParams | Camera parameters |
markerSizeMeters | size of the marker sides expressed in meters |
setYPerperdicular | If set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis |
correctFisheye | Correct fisheye distortion |
Definition at line 141 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::detect | ( | const cv::Mat & | input, |
std::vector< Marker > & | detectedMarkers, | ||
cv::Mat | camMatrix = cv::Mat() , |
||
cv::Mat | distCoeff = cv::Mat() , |
||
cv::Mat | extrinsics = cv::Mat() , |
||
float | markerSizeMeters = -1 , |
||
bool | setYPerperdicular = false , |
||
bool | correctFisheye = false |
||
) |
Detects the markers in the image passed
If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected
NOTE: be sure that the camera matrix is for this image size. If you do not know what I am talking about, use functions above and not this one
input | input color image |
detectedMarkers | output vector with the markers detected |
camMatrix | intrinsic camera information. |
distCoeff | camera distorsion coefficient. If set Mat() if is assumed no camera distorion |
extrinsics | translation (tx,ty,tz) from right stereo camera to left. Empty if no stereo or left camera |
markerSizeMeters | size of the marker sides expressed in meters |
setYPerperdicular | If set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis |
correctFisheye | Correct fisheye distortion |
CREATE LOW RESOLUTION IMAGE IN WHICH MARKERS WILL BE DETECTED
THRESHOLD IMAGES AND DETECT INITIAL RECTANGLES
CANDIDATE CLASSIFICATION: Decide which candidates are really markers
MARKER Tracking
REMOVAL OF DUPLICATED
CORNER REFINEMENT IF REQUIRED /////////////////////////////////////////////////////////////////// refine the corner location if enclosed markers and we did not do it via upsampling
MARKER POSE ESTIMATION
detect the position of detected markers if desired
save for tracking
Definition at line 781 of file markerdetector_impl.cpp.
|
private |
Definition at line 1686 of file markerdetector_impl.cpp.
|
private |
Definition at line 1632 of file markerdetector_impl.cpp.
|
private |
Definition at line 1599 of file markerdetector_impl.cpp.
|
private |
Definition at line 1618 of file markerdetector_impl.cpp.
|
private |
Definition at line 1610 of file markerdetector_impl.cpp.
|
private |
Definition at line 1344 of file markerdetector_impl.cpp.
|
private |
Definition at line 1743 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::fromStream | ( | std::istream & | str | ) |
Definition at line 1731 of file markerdetector_impl.cpp.
|
inline |
Returns a list candidates to be markers (rectangles), for which no valid id was found after calling detectRectangles
Definition at line 235 of file markerdetector_impl.h.
|
private |
Definition at line 1532 of file markerdetector_impl.cpp.
DetectionMode aruco::MarkerDetector_Impl::getDetectionMode | ( | ) |
returns current detection mode
Definition at line 104 of file markerdetector_impl.cpp.
|
inline |
Definition at line 257 of file markerdetector_impl.h.
|
inline |
Definition at line 225 of file markerdetector_impl.h.
|
private |
Definition at line 159 of file markerdetector_impl.cpp.
|
private |
Definition at line 1414 of file markerdetector_impl.cpp.
|
inline |
Returns operating params
Definition at line 171 of file markerdetector_impl.h.
|
inline |
Returns operating params
Definition at line 165 of file markerdetector_impl.h.
cv::Mat aruco::MarkerDetector_Impl::getThresholdedImage | ( | uint32_t | idx = 0 | ) |
Returns a reference to the internal image thresholded. Since there can be generated many of them, specify which
Definition at line 1673 of file markerdetector_impl.cpp.
|
private |
Definition at line 1474 of file markerdetector_impl.cpp.
|
inlineprivate |
Definition at line 313 of file markerdetector_impl.h.
void aruco::MarkerDetector_Impl::loadParamsFromFile | ( | const std::string & | path | ) |
Loads the configuration from a file.
Loads the configuration from a file
Definition at line 1715 of file markerdetector_impl.cpp.
|
private |
Definition at line 739 of file markerdetector_impl.cpp.
|
private |
Definition at line 1459 of file markerdetector_impl.cpp.
|
inlineprivate |
Definition at line 416 of file markerdetector_impl.h.
|
private |
CANDIDATE PREFILTERING- Merge and Remove candidates so that only reliable ones are returned /////////////////////////////////////////////////////////////////////////////// sort the points in anti-clockwise order
remove these elements which corners are too close to each other
mark for removal the element of the pair with smaller perimeter
find these too near borders and remove them
Definition at line 641 of file markerdetector_impl.cpp.
|
private |
Definition at line 1243 of file markerdetector_impl.cpp.
|
inlineprivate |
Given a vector vinout with elements and a boolean vector indicating the lements from it to remove, this function remove the elements
vinout | |
toRemove |
Definition at line 295 of file markerdetector_impl.h.
void aruco::MarkerDetector_Impl::saveParamsToFile | ( | const std::string & | path | ) | const |
Saves the configuration of the detector to a file.
Saves the configuration of the detector to a file
Definition at line 1705 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::setDetectionMode | ( | DetectionMode | dm, |
float | minMarkerSize = 0 |
||
) |
Specifies the detection mode. We have preset three types of detection modes. These are ways to configure the internal parameters for the most typical situations. The modes are:
Definition at line 99 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::setDictionary | ( | int | dict_type, |
float | error_correction_rate = 0 |
||
) |
setDictionary Specifies the dictionary you want to use for marker decoding
dict_type | dictionary employed for decoding markers |
error_correction_rate | value indicating the correction error allowed. Is in range [0,1]. 0 means no correction at all. So an erroneous bit will result in discarding the marker. 1, mean full correction. The maximum number of bits that can be corrected depends on each ditionary. We recommend using values from 0 to 0.5. (in general, this will allow up to 3 bits or correction). |
Definition at line 1649 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::setDictionary | ( | std::string | dict_type, |
float | error_correction_rate = 0 |
||
) |
Sets the dictionary to be employed. You can choose:ARUCO,//original aruco dictionary. By default ARUCO_MIP_25h7, ARUCO_MIP_16h3, ARUCO_MIP_36h12, **** recommended ARTAG,// ARTOOLKITPLUS, ARTOOLKITPLUSBCH,// TAG16h5,TAG25h7,TAG25h9,TAG36h11,TAG36h10//APRIL TAGS DICIONARIES CHILITAGS,//chili tags dictionary . NOT RECOMMENDED. It has distance 0. Markers 806 and 682 should not be used!!!
If dict_type is none of the above ones, it is assumed you mean a CUSTOM dicionary saved in a file
void aruco::MarkerDetector_Impl::setMarkerLabeler | ( | cv::Ptr< MarkerLabeler > | detector | ) |
setMakerLabeler sets the labeler employed to analyze the squares and extract the inner binary code
returns the number of thresholed images available
Methods you may not need
detector |
Definition at line 1644 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::setParameters | ( | const MarkerDetector::Params & | params | ) |
Definition at line 87 of file markerdetector_impl.cpp.
|
private |
Definition at line 556 of file markerdetector_impl.cpp.
|
private |
kpts.erase(std::remove_if(kpts.begin(),kpts.end(), [ ](const cv::KeyPoint &kp){return kp.class_id==0;}), kpts.end());
for each contour, analyze if it is a paralelepiped likely to be the marker
Definition at line 422 of file markerdetector_impl.cpp.
|
private |
Definition at line 540 of file markerdetector_impl.cpp.
void aruco::MarkerDetector_Impl::toStream | ( | std::ostream & | str | ) | const |
Definition at line 1724 of file markerdetector_impl.cpp.
bool aruco::MarkerDetector_Impl::warp | ( | cv::Mat & | in, |
cv::Mat & | out, | ||
cv::Size | size, | ||
std::vector< cv::Point2f > | points | ||
) |
Given the iput image with markers, creates an output image with it in the canonical position
in | input image |
out | image with the marker |
size | of out |
points | 4 corners of the marker in the image in |
Definition at line 1433 of file markerdetector_impl.cpp.
|
friend |
Definition at line 43 of file markerdetector_impl.h.
|
private |
Definition at line 347 of file markerdetector_impl.h.
|
private |
Definition at line 268 of file markerdetector_impl.h.
|
private |
Definition at line 348 of file markerdetector_impl.h.
|
private |
Definition at line 412 of file markerdetector_impl.h.
|
private |
Definition at line 344 of file markerdetector_impl.h.
|
private |
Definition at line 423 of file markerdetector_impl.h.
|
private |
Definition at line 345 of file markerdetector_impl.h.
|
private |
Definition at line 271 of file markerdetector_impl.h.
|
private |
Definition at line 322 of file markerdetector_impl.h.
|
private |
Definition at line 349 of file markerdetector_impl.h.
|
private |
Definition at line 273 of file markerdetector_impl.h.
|
private |
Definition at line 271 of file markerdetector_impl.h.