Classes | Public Types | Public Member Functions | Private Attributes | Friends | List of all members
aruco::MarkerDetector Class Reference

Main class for marker detection. More...

#include <markerdetector.h>

Classes

struct  Params
 

Public Types

enum  ThresMethod : int { THRES_ADAPTIVE = 0, THRES_AUTO_FIXED = 1 }
 

Public Member Functions

void cornerUpsample (std::vector< Marker > &corners, cv::Size lowResImageSize)
 
void cornerUpsample (std::vector< std::vector< cv::Point2f > > &corners, cv::Size lowResImageSize)
 
std::vector< aruco::Markerdetect (const cv::Mat &input)
 
std::vector< aruco::Markerdetect (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< MarkerCandidategetCandidates () const
 
DetectionMode getDetectionMode ()
 
std::vector< cv::Mat > getImagePyramid ()
 
cv::Ptr< MarkerLabelergetMarkerLabeler ()
 
ParamsgetParameters ()
 
Params getParameters () const
 
cv::Mat getThresholdedImage (uint32_t idx=0)
 
void loadParamsFromFile (const std::string &path)
 
 MarkerDetector ()
 
 MarkerDetector (int dict_type, float error_correction_rate=0)
 
 MarkerDetector (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 Params &params)
 
void toStream (std::ostream &str) const
 
bool warp (cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points)
 
 ~MarkerDetector ()
 

Private Attributes

MarkerDetector_Impl_impl
 

Friends

class MarkerDetector_Impl
 

Detailed Description

Main class for marker detection.

Definition at line 91 of file markerdetector.h.

Member Enumeration Documentation

◆ ThresMethod

Enumerator
THRES_ADAPTIVE 
THRES_AUTO_FIXED 

Definition at line 96 of file markerdetector.h.

Constructor & Destructor Documentation

◆ MarkerDetector() [1/3]

aruco::MarkerDetector::MarkerDetector ( )

See

Definition at line 49 of file markerdetector.cpp.

◆ MarkerDetector() [2/3]

aruco::MarkerDetector::MarkerDetector ( int  dict_type,
float  error_correction_rate = 0 
)

Creates indicating the dictionary. See

See also
setDictionary for further details
Parameters
dict_typeDictionary employed. See
See also
setDictionary for further details
Parameters
error_correction_ratevalue 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.cpp.

◆ MarkerDetector() [3/3]

aruco::MarkerDetector::MarkerDetector ( std::string  dict_type,
float  error_correction_rate = 0 
)

Definition at line 72 of file markerdetector.cpp.

◆ ~MarkerDetector()

aruco::MarkerDetector::~MarkerDetector ( )

Definition at line 85 of file markerdetector.cpp.

Member Function Documentation

◆ cornerUpsample() [1/2]

void aruco::MarkerDetector::cornerUpsample ( std::vector< Marker > &  corners,
cv::Size  lowResImageSize 
)

◆ cornerUpsample() [2/2]

void aruco::MarkerDetector::cornerUpsample ( std::vector< std::vector< cv::Point2f > > &  corners,
cv::Size  lowResImageSize 
)

Definition at line 456 of file markerdetector.cpp.

◆ detect() [1/4]

std::vector< aruco::Marker > aruco::MarkerDetector::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

Parameters
inputinput color image
camMatrixintrinsic camera information.
distCoeffcamera distorsion coefficient. If set Mat() if is assumed no camera distorion
markerSizeMeterssize of the marker sides expressed in meters. If not specified this value, the extrinsics of the markers are not detected.
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
correctFisheyeCorrect fisheye distortion
Returns
vector with the detected markers

Definition at line 120 of file markerdetector.cpp.

◆ detect() [2/4]

std::vector< aruco::Marker > aruco::MarkerDetector::detect ( const cv::Mat &  input,
const CameraParameters camParams,
float  markerSizeMeters,
bool  setYPerperdicular = false,
bool  correctFisheye = false 
)

Definition at line 125 of file markerdetector.cpp.

◆ detect() [3/4]

void aruco::MarkerDetector::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

Parameters
inputinput color image
detectedMarkersoutput vector with the markers detected
camParamsCamera parameters
markerSizeMeterssize of the marker sides expressed in meters
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
correctFisheyeCorrect fisheye distortion

Definition at line 139 of file markerdetector.cpp.

◆ detect() [4/4]

void aruco::MarkerDetector::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

Parameters
inputinput color image
detectedMarkersoutput vector with the markers detected
camMatrixintrinsic camera information.
distCoeffcamera distortion coefficient. If set Mat() if is assumed no camera distortion
extrinsicstranslation (tx,ty,tz) from right stereo camera to left. Empty if no stereo or left camera
markerSizeMeterssize of the marker sides expressed in meters
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
correctFisheyeCorrect fisheye distortion

◆ fromStream()

void aruco::MarkerDetector::fromStream ( std::istream &  str)

Definition at line 328 of file markerdetector.cpp.

◆ getCandidates()

std::vector< MarkerCandidate > aruco::MarkerDetector::getCandidates ( ) const

Returns a list candidates to be markers (rectangles), for which no valid id was found after calling detectRectangles

Definition at line 159 of file markerdetector.cpp.

◆ getDetectionMode()

DetectionMode aruco::MarkerDetector::getDetectionMode ( )

returns current detection mode

Definition at line 106 of file markerdetector.cpp.

◆ getImagePyramid()

std::vector< cv::Mat > aruco::MarkerDetector::getImagePyramid ( )

Definition at line 164 of file markerdetector.cpp.

◆ getMarkerLabeler()

cv::Ptr< MarkerLabeler > aruco::MarkerDetector::getMarkerLabeler ( )

Definition at line 168 of file markerdetector.cpp.

◆ getParameters() [1/2]

Params& aruco::MarkerDetector::getParameters ( )

Returns operating params

◆ getParameters() [2/2]

MarkerDetector::Params & aruco::MarkerDetector::getParameters ( ) const

Returns operating params

Definition at line 148 of file markerdetector.cpp.

◆ getThresholdedImage()

cv::Mat aruco::MarkerDetector::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 187 of file markerdetector.cpp.

◆ loadParamsFromFile()

void aruco::MarkerDetector::loadParamsFromFile ( const std::string &  path)

Loads the configuration from a file.

Loads the configuration from a file

Definition at line 318 of file markerdetector.cpp.

◆ saveParamsToFile()

void aruco::MarkerDetector::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 311 of file markerdetector.cpp.

◆ setDetectionMode()

void aruco::MarkerDetector::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:

  • DM_NORMAL: In this mode, the full resolution image is employed for detection and slow threshold method. Use this method when you process individual images that are not part of a video sequence and you are not interested in speed.
  • DM_FAST: In this mode, there are two main improvements. First, image is threshold using a faster method using a global threshold. Also, the full resolution image is employed for detection, but, you could speed up detection even more by indicating a minimum size of the markers you will accept. This is set by the variable minMarkerSize which shoud be in range [0,1]. When it is 0, means that you do not set a limit in the size of the accepted markers. However, if you set 0.1, it means that markers smaller than 10% of the total image area, will not be detected. Then, the detection can be accelated up to orders of magnitude compared to the normal mode.
  • DM_VIDEO_FAST: This is similar to DM_FAST, but specially adapted to video processing. In that case, we assume that the observed markers when you call to detect() have a size similar to the ones observed in the previous frame. Then, the processing can be speeded up by employing smaller versions of the image automatically calculated.

Definition at line 101 of file markerdetector.cpp.

◆ setDictionary() [1/2]

void aruco::MarkerDetector::setDictionary ( int  dict_type,
float  error_correction_rate = 0 
)

setDictionary Specifies the dictionary you want to use for marker decoding

Parameters
dict_typedictionary employed for decoding markers
See also
Dictionary
Parameters
error_correction_ratevalue 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 177 of file markerdetector.cpp.

◆ setDictionary() [2/2]

void aruco::MarkerDetector::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

See also
Dictionary::loadFromFile Then, it tries to open it

◆ setMarkerLabeler()

void aruco::MarkerDetector::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

Thesde methods do the hard work. They have been set public in case you want to do customizations

Parameters
detector

Definition at line 172 of file markerdetector.cpp.

◆ setParameters()

void aruco::MarkerDetector::setParameters ( const Params params)

Definition at line 90 of file markerdetector.cpp.

◆ toStream()

void aruco::MarkerDetector::toStream ( std::ostream &  str) const

Definition at line 323 of file markerdetector.cpp.

◆ warp()

bool aruco::MarkerDetector::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

Parameters
ininput image
outimage with the marker
sizeof out
points4 corners of the marker in the image in
Returns
true if the operation succeed

Friends And Related Function Documentation

◆ MarkerDetector_Impl

friend class MarkerDetector_Impl
friend

Definition at line 93 of file markerdetector.h.

Member Data Documentation

◆ _impl

MarkerDetector_Impl* aruco::MarkerDetector::_impl
private

Definition at line 460 of file markerdetector.h.


The documentation for this class was generated from the following files:


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:45