Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpDetectorAprilTag Class Reference

#include <vpDetectorAprilTag.h>

Inheritance diagram for vpDetectorAprilTag:

Public Types

enum  vpAprilTagFamily {
  TAG_36h11 , TAG_36h10 , TAG_36ARTOOLKIT , TAG_25h9 ,
  TAG_25h7 , TAG_16h5 , TAG_CIRCLE21h7 , TAG_CIRCLE49h12 ,
  TAG_CUSTOM48h12 , TAG_STANDARD41h12 , TAG_STANDARD52h13 , TAG_ARUCO_4x4_50 ,
  TAG_ARUCO_4x4_100 , TAG_ARUCO_4x4_250 , TAG_ARUCO_4x4_1000 , TAG_ARUCO_5x5_50 ,
  TAG_ARUCO_5x5_100 , TAG_ARUCO_5x5_250 , TAG_ARUCO_5x5_1000 , TAG_ARUCO_6x6_50 ,
  TAG_ARUCO_6x6_100 , TAG_ARUCO_6x6_250 , TAG_ARUCO_6x6_1000 , TAG_ARUCO_7x7_50 ,
  TAG_ARUCO_7x7_100 , TAG_ARUCO_7x7_250 , TAG_ARUCO_7x7_1000 , TAG_ARUCO_MIP_36h12
}
enum  vpPoseEstimationMethod {
  HOMOGRAPHY , HOMOGRAPHY_VIRTUAL_VS , DEMENTHON_VIRTUAL_VS , LAGRANGE_VIRTUAL_VS ,
  BEST_RESIDUAL_VIRTUAL_VS , HOMOGRAPHY_ORTHOGONAL_ITERATION
}

Public Member Functions

 vpDetectorAprilTag (const vpAprilTagFamily &tagFamily=TAG_36h11, const vpPoseEstimationMethod &poseEstimationMethod=HOMOGRAPHY_VIRTUAL_VS)
 vpDetectorAprilTag (const vpDetectorAprilTag &o)
vpDetectorAprilTagoperator= (vpDetectorAprilTag o)
virtual ~vpDetectorAprilTag () VP_OVERRIDE
bool detect (const vpImage< unsigned char > &I) VP_OVERRIDE
bool detect (const vpImage< unsigned char > &I, double tagSize, const vpCameraParameters &cam, std::vector< vpHomogeneousMatrix > &cMo_vec, std::vector< vpHomogeneousMatrix > *cMo_vec2=nullptr, std::vector< double > *projErrors=nullptr, std::vector< double > *projErrors2=nullptr)
void displayFrames (const vpImage< unsigned char > &I, const std::vector< vpHomogeneousMatrix > &cMo_vec, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness=1) const
void displayFrames (const vpImage< vpRGBa > &I, const std::vector< vpHomogeneousMatrix > &cMo_vec, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness=1) const
void displayTags (const vpImage< unsigned char > &I, const std::vector< std::vector< vpImagePoint > > &tagsCorners, const vpColor &color=vpColor::none, unsigned int thickness=1) const
void displayTags (const vpImage< vpRGBa > &I, const std::vector< std::vector< vpImagePoint > > &tagsCorners, const vpColor &color=vpColor::none, unsigned int thickness=1) const
float getAprilTagDecisionMarginThreshold () const
int getAprilTagHammingDistanceThreshold () const
bool getPose (size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, vpHomogeneousMatrix *cMo2=nullptr, double *projError=nullptr, double *projError2=nullptr)
vpPoseEstimationMethod getPoseEstimationMethod () const
bool getTagImage (vpImage< unsigned char > &I, int id)
std::vector< std::vector< vpImagePoint > > getTagsCorners () const
std::vector< float > getTagsDecisionMargin () const
std::vector< int > getTagsHammingDistance () const
std::vector< int > getTagsId () const
std::vector< std::vector< vpPoint > > getTagsPoints3D (const std::vector< int > &tagsId, const std::map< int, double > &tagsSize) const
bool isZAlignedWithCameraAxis () const
void setAprilTagDebugOption (bool flag)
void setAprilTagDecisionMarginThreshold (float decisionMarginThreshold)
void setAprilTagDecodeSharpening (double decodeSharpening)
void setAprilTagFamily (const vpAprilTagFamily &tagFamily)
void setAprilTagHammingDistanceThreshold (int hammingDistanceThreshold)
void setAprilTagNbThreads (int nThreads)
void setAprilTagPoseEstimationMethod (const vpPoseEstimationMethod &poseEstimationMethod)
void setAprilTagQuadDecimate (float quadDecimate)
void setAprilTagQuadSigma (float quadSigma)
void setAprilTagRefineEdges (bool refineEdges)
void setDisplayTag (bool display, const vpColor &color=vpColor::none, unsigned int thickness=2)
void setZAlignedWithCameraAxis (bool zAlignedWithCameraFrame)

Friends

void swap (vpDetectorAprilTag &o1, vpDetectorAprilTag &o2)

Deprecated functions

bool m_displayTag
vpColor m_displayTagColor
unsigned int m_displayTagThickness
vpPoseEstimationMethod m_poseEstimationMethod
vpAprilTagFamily m_tagFamily
VP_DEPRECATED void setAprilTagRefinePose (bool refinePose)
VP_DEPRECATED void setAprilTagRefineDecode (bool refineDecode)

Inherited functionalities from vpDetectorBase

std::vector< std::vector< vpImagePoint > > m_polygon
std::vector< std::string > m_message
size_t m_nb_objects
unsigned long m_timeout_ms
vpRect getBBox (size_t i) const
vpImagePoint getCog (size_t i) const
std::vector< std::string > & getMessage ()
std::string & getMessage (size_t i)
size_t getNbObjects () const
std::vector< std::vector< vpImagePoint > > & getPolygon ()
std::vector< vpImagePoint > & getPolygon (size_t i)
void setTimeout (unsigned long timeout_ms)

Detailed Description

Base class for AprilTag detector. This class is a wrapper over AprilTag. There is no need to download and install AprilTag from source code or from existing pre-built packages since the source code is embedded in ViSP. Reference papers are AprilTag: A robust and flexible visual fiducial system ([42]), AprilTag 2: Efficient and robust fiducial detection ([58]) and Flexible Layouts for Fiducial Tags ([25]).

Supported tag families are the following:

  • AprilTag 16h5
  • AprilTag 25h9
  • AprilTag 36h10 (deprecated)
  • AprilTag 36h11
  • AprilTag Circle_21h7 (AprilTag 3)
  • AprilTag Circle_49h12 (AprilTag 3, CMake WITH_APRILTAG_BIG_FAMILY var must be set to true)
  • AprilTag Custom_48h12 (AprilTag 3, CMake WITH_APRILTAG_BIG_FAMILY var must be set to true)
  • AprilTag Standard_41h12 (AprilTag 3, CMake WITH_APRILTAG_BIG_FAMILY var must be set to true)
  • AprilTag Standard_52h13 (AprilTag 3, CMake WITH_APRILTAG_BIG_FAMILY var must be set to true)
  • ArUco 4x4
  • ArUco 5x5
  • ArUco 6x6
  • ArUco 7x7
  • ArUco MIP_36h12
    Supported tags with id 0.

To use this class you can follow Tutorial: AprilTag/ArUco marker detection.

The detect() function allows to detect multiple tags in an image. Once detected, for each tag it is possible to retrieve the location of the corners using getPolygon(), the encoded message using getMessage(), the bounding box using getBBox() and the center of gravity using getCog().

If camera parameters and the size of the tag are provided, you can also estimate the 3D pose of the tag in terms of position and orientation wrt the camera considering 2 cases:

  1. If all the tags have the same size use detect(const vpImage<unsigned char> &, double, const vpCameraParameters &, std::vector<vpHomogeneousMatrix> &, std::vector<vpHomogeneousMatrix> *, std::vector<double> *, std::vector<double> *)
  2. If tag sizes differ, use rather getPose()
Note
With ViSP, the size of the tag corresponds to the black part of the tag. Note also that to be detected, the black part of the tag must be surrounded by a white border as wide as the black border as in the next image:

The following sample code shows how to use this class to detect the location of 36h11 AprilTag patterns in an image.

#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/io/vpImageIo.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#ifdef VISP_HAVE_APRILTAG
vpImageIo::read(I, "image-tag36h11.pgm");
bool status = detector.detect(I);
if (status) {
for(size_t i=0; i < detector.getNbObjects(); ++i) {
std::cout << "Tag code " << i << ":" << std::endl;
std::vector<vpImagePoint> p = detector.getPolygon(i);
for(size_t j=0; j < p.size(); ++j)
std::cout << " Point " << j << ": " << p[j] << std::endl;
std::cout << " Message: \"" << detector.getMessage(i) << "\"" << std::endl;
}
}
#endif
}
vpDetectorAprilTag(const vpAprilTagFamily &tagFamily=TAG_36h11, const vpPoseEstimationMethod &poseEstimationMethod=HOMOGRAPHY_VIRTUAL_VS)
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition of the vpImage class member functions.
Definition vpImage.h:131

The previous example may produce results like:

Tag code 0:
Point 0: 124.008, 442.226
Point 1: 194.614, 441.237
Point 2: 184.833, 540.386
Point 3: 111.948, 533.634
Message: "36h11 id: 0"
Tag code 1:
Point 0: 245.327, 438.801
Point 1: 338.116, 437.221
Point 2: 339.341, 553.539
Point 3: 238.954, 543.855
Message: "36h11 id: 1"

As shown in the next image, two different tag frames could be considered for pose estimation.

Tag 36h11_00000 with location of the 4 corners and tag frame

There is the function setZAlignedWithCameraAxis() that allows to choose which tag frame has to be considered.

This other example shows how to estimate the 3D pose of 36h11 AprilTag patterns considering that all the tags have the same size (in our example 0.053 m). Here we consider the default case, when z-camera and z-tag axis are not aligned.

#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/io/vpImageIo.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#ifdef VISP_HAVE_APRILTAG
vpImageIo::read(I, "image-tag36h11.pgm");
detector.setZAlignedWithCameraAxis(false); // Default configuration
std::vector<vpHomogeneousMatrix> cMo;
cam.initPersProjWithoutDistortion(615.1674805, 615.1675415, 312.1889954, 243.4373779);
double tagSize = 0.053;
bool status = detector.detect(I, tagSize, cam, cMo);
if (status) {
for(size_t i=0; i < detector.getNbObjects(); ++i) {
std::cout << "Tag number " << i << ":" << std::endl;
std::cout << " Message: \"" << detector.getMessage(i) << "\"" << std::endl;
std::cout << " Pose: " << vpPoseVector(cMo[i]).t() << std::endl;
std::size_t tag_id_pos = detector.getMessage(i).find("id: ");
if (tag_id_pos != std::string::npos) {
std::string tag_id = detector.getMessage(i).substr(tag_id_pos + 4);
std::cout << " Tag Id: " << tag_id << std::endl;
}
}
}
#endif
}
Generic class defining intrinsic camera parameters.
Implementation of a pose vector and operations on poses.
vpRowVector t() const

The previous example may produce results like:

Tag number 0:
Message: "36h11 id: 0"
Pose: 0.1015061088 -0.05239057228 0.3549037285 1.991474322 2.04143538 -0.9412360063
Tag Id: 0
Tag number 1:
Message: "36h11 id: 1"
Pose: 0.08951250829 0.02243780207 0.306540622 1.998073197 2.061488008 -0.8699567948
Tag Id: 1

In this other example we estimate the 3D pose of 36h11 AprilTag patterns considering that tag 36h11 with id 0 (in that case the tag message is "36h11 id: 0") has a size of 0.040 m, while all the others have a size of 0.053m.

#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/io/vpImageIo.h>
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
int main()
{
#ifdef VISP_HAVE_APRILTAG
vpImageIo::read(I, "image-tag36h11.pgm");
cam.initPersProjWithoutDistortion(615.1674805, 615.1675415, 312.1889954, 243.4373779);
double tagSize_id_0 = 0.04;
double tagSize_id_others = 0.053;
bool status = detector.detect(I);
if (status) {
for(size_t i=0; i < detector.getNbObjects(); ++i) {
std::cout << "Tag code " << i << ":" << std::endl;
std::cout << " Message: \"" << detector.getMessage(i) << "\"" << std::endl;
if (detector.getMessage(i) == std::string("36h11 id: 0")) {
if (! detector.getPose(i, tagSize_id_0, cam, cMo)) {
std::cout << "Unable to get tag index " << i << " pose!" << std::endl;
}
}
else {
if (! detector.getPose(i, tagSize_id_others, cam, cMo)) {
std::cout << "Unable to get tag index " << i << " pose!" << std::endl;
}
}
std::cout << " Pose: " << vpPoseVector(cMo).t() << std::endl;
}
}
#endif
}
Implementation of an homogeneous matrix and operations on such kind of matrices.

With respect to the previous example, this example may now produce a different pose for tag with id 0:

Tag code 0:
Message: "36h11 id: 0"
Pose: 0.07660838403 -0.03954005455 0.2678518706 1.991474322 2.04143538 -0.9412360063
Tag code 1:
Message: "36h11 id: 1"
Pose: 0.08951250829 0.02243780207 0.306540622 1.998073197 2.061488008 -0.8699567948

Tutorials & Examples

Tutorials
If you want a detailed explanation on how to use this class, you may have a look at:

Examples
catchAprilTag.cpp, catchArUco.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, perfApriltagDetection.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoBebop2.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVf_fVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Ldes_cVf_fVe_eJe.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPixhawkDroneIBVS.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, tutorial-apriltag-detector-live-T265-realsense.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, tutorial-apriltag-detector-live.cpp, tutorial-apriltag-detector.cpp, tutorial-create-tag-image.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, and visp-compute-apriltag-poses.cpp.

Definition at line 261 of file vpDetectorAprilTag.h.

Member Enumeration Documentation

◆ vpAprilTagFamily

Enumerator
TAG_36h11 

AprilTag 36h11 pattern (recommended).

TAG_36h10 

DEPRECATED.

TAG_36ARTOOLKIT 

DEPRECATED AND WILL NOT DETECT ARTOOLKIT TAGS.

TAG_25h9 

AprilTag 25h9 pattern.

TAG_25h7 

DEPRECATED AND POOR DETECTION PERFORMANCE.

TAG_16h5 

AprilTag 16h5 pattern.

TAG_CIRCLE21h7 

AprilTag Circle21h7 pattern.

TAG_CIRCLE49h12 

AprilTag Circle49h12 pattern.

TAG_CUSTOM48h12 

AprilTag Custom48h12 pattern.

TAG_STANDARD41h12 

AprilTag Standard41h12 pattern.

TAG_STANDARD52h13 

AprilTag Standard52h13 pattern.

TAG_ARUCO_4x4_50 

ArUco 4x4 pattern: 4x4 bits, minimum hamming distance between any two codes = 4, 50 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_4x4_100 

ArUco 4x4 pattern: 4x4 bits, minimum hamming distance between any two codes = 3, 100 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_4x4_250 

ArUco 4x4 pattern: 4x4 bits, minimum hamming distance between any two codes = 3, 250 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_4x4_1000 

ArUco 4x4 pattern: 4x4 bits, minimum hamming distance between any two codes = 2, 1000 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_5x5_50 

ArUco 5x5 pattern: 5x5 bits, minimum hamming distance between any two codes = 8, 50 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_5x5_100 

ArUco 5x5 pattern: 5x5 bits, minimum hamming distance between any two codes = 7, 100 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_5x5_250 

ArUco 5x5 pattern: 5x5 bits, minimum hamming distance between any two codes = 6, 250 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_5x5_1000 

ArUco 5x5 pattern: 5x5 bits, minimum hamming distance between any two codes = 5, 1000 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_6x6_50 

ArUco 6x6 pattern: 6x6 bits, minimum hamming distance between any two codes = 13, 50 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_6x6_100 

ArUco 6x6 pattern: 6x6 bits, minimum hamming distance between any two codes = 12, 100 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_6x6_250 

ArUco 6x6 pattern: 6x6 bits, minimum hamming distance between any two codes = 11, 250 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_6x6_1000 

ArUco 6x6 pattern: 6x6 bits, minimum hamming distance between any two codes = 9, 1000 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_7x7_50 

ArUco 7x7 pattern: 7x7 bits, minimum hamming distance between any two codes = 19, 50 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_7x7_100 

ArUco 7x7 pattern: 7x7 bits, minimum hamming distance between any two codes = 18, 100 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_7x7_250 

ArUco 7x7 pattern: 7x7 bits, minimum hamming distance between any two codes = 17, 250 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_7x7_1000 

ArUco 7x7 pattern: 7x7 bits, minimum hamming distance between any two codes = 14, 1000 codes.
This tag family can produce lots of false detections which can be filtered by setting an appropriate decision margin, using setAprilTagDecisionMarginThreshold() or getTagsDecisionMargin(). See 4.1. Filter out false positive detections section for more details.

TAG_ARUCO_MIP_36h12 

ArUco 6x6 pattern: 6x6 bits, minimum hamming distance between any two codes = 12, 250 codes.
This is the recommended ArUco tag family by the main ArUco developer, see this link

Examples
catchAprilTag.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoBebop2.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVf_fVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Ldes_cVf_fVe_eJe.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPixhawkDroneIBVS.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, tutorial-apriltag-detector-live-T265-realsense.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, tutorial-apriltag-detector-live.cpp, tutorial-apriltag-detector.cpp, tutorial-create-tag-image.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, and visp-compute-apriltag-poses.cpp.

Definition at line 264 of file vpDetectorAprilTag.h.

◆ vpPoseEstimationMethod

Enumerator
HOMOGRAPHY 

Pose from homography

HOMOGRAPHY_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by the homography approach

DEMENTHON_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by the Dementhon approach

LAGRANGE_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by the Lagrange approach

BEST_RESIDUAL_VIRTUAL_VS 

Non linear virtual visual servoing approach initialized by the approach that gives the lowest residual

HOMOGRAPHY_ORTHOGONAL_ITERATION 

Pose from homography followed by a refinement by Orthogonal Iteration

Examples
catchAprilTag.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-pbvs.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoFlirPtuIBVS.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Lcur_cVf_fVe_eJe.cpp, servoFrankaIBVS-EyeToHand-Ldes_cVf_fVe_eJe.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, tutorial-apriltag-detector-live-T265-realsense.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live-rgbd-structure-core.cpp, tutorial-apriltag-detector-live.cpp, tutorial-apriltag-detector.cpp, and visp-compute-apriltag-poses.cpp.

Definition at line 346 of file vpDetectorAprilTag.h.

Constructor & Destructor Documentation

◆ vpDetectorAprilTag() [1/2]

BEGIN_VISP_NAMESPACE vpDetectorAprilTag::vpDetectorAprilTag ( const vpAprilTagFamily & tagFamily = TAG_36h11,
const vpPoseEstimationMethod & poseEstimationMethod = HOMOGRAPHY_VIRTUAL_VS )

◆ vpDetectorAprilTag() [2/2]

◆ ~vpDetectorAprilTag()

vpDetectorAprilTag::~vpDetectorAprilTag ( )
virtual

Definition at line 1188 of file vpDetectorAprilTag.cpp.

Member Function Documentation

◆ detect() [1/2]

bool vpDetectorAprilTag::detect ( const vpImage< unsigned char > & I)
virtual

◆ detect() [2/2]

bool vpDetectorAprilTag::detect ( const vpImage< unsigned char > & I,
double tagSize,
const vpCameraParameters & cam,
std::vector< vpHomogeneousMatrix > & cMo_vec,
std::vector< vpHomogeneousMatrix > * cMo_vec2 = nullptr,
std::vector< double > * projErrors = nullptr,
std::vector< double > * projErrors2 = nullptr )

Detect AprilTag tags in the image and compute the corresponding tag poses considering that all the tags have the same size.

If tags with different sizes have to be considered, you may use getPose().

Parameters
[in]I: Input image.
[in]tagSize: Tag size in meter corresponding to the external width of the pattern.
[in]cam: Camera intrinsic parameters.
[out]cMo_vec: List of tag poses.
[out]cMo_vec2: Optional second list of tag poses, since there are 2 solutions for planar pose estimation.
[out]projErrors: Optional (sum of squared) projection errors in the normalized camera frame.
[out]projErrors2: Optional (sum of squared) projection errors for the 2nd solution in the normalized camera frame.
Returns
true if at least one tag is detected.
See also
getPose()

Definition at line 1229 of file vpDetectorAprilTag.cpp.

References m_displayTag, m_displayTagColor, m_displayTagThickness, vpDetectorBase::m_message, vpDetectorBase::m_nb_objects, and vpDetectorBase::m_polygon.

Referenced by visp.python.rbt.xfeat.XFeatTrackingBackend.XFeatTrackingBackend::process_frame().

◆ displayFrames() [1/2]

void vpDetectorAprilTag::displayFrames ( const vpImage< unsigned char > & I,
const std::vector< vpHomogeneousMatrix > & cMo_vec,
const vpCameraParameters & cam,
double size,
const vpColor & color,
unsigned int thickness = 1 ) const

Display the tag frames on a grayscale image.

Parameters
[in]I: The image.
[in]cMo_vec: The vector of computed tag poses.
[in]cam: Camera intrinsic parameters.
[out]size: Size of the frame.
[out]color: The desired color, if none the X-axis is red, the Y-axis green and the Z-axis blue.
[out]thickness: The thickness of the lines.

Definition at line 1258 of file vpDetectorAprilTag.cpp.

◆ displayFrames() [2/2]

void vpDetectorAprilTag::displayFrames ( const vpImage< vpRGBa > & I,
const std::vector< vpHomogeneousMatrix > & cMo_vec,
const vpCameraParameters & cam,
double size,
const vpColor & color,
unsigned int thickness = 1 ) const

Display the tag frames on a vpRGBa image.

Parameters
[in]I: The image.
[in]cMo_vec: The vector of computed tag poses.
[in]cam: Camera intrinsic parameters.
[out]size: Size of the frame.
[out]color: The desired color, if none the X-axis is red, the Y-axis green and the Z-axis blue.
[out]thickness: The thickness of the lines.

Definition at line 1274 of file vpDetectorAprilTag.cpp.

◆ displayTags() [1/2]

void vpDetectorAprilTag::displayTags ( const vpImage< unsigned char > & I,
const std::vector< std::vector< vpImagePoint > > & tagsCorners,
const vpColor & color = vpColor::none,
unsigned int thickness = 1 ) const

Display the tag contours on a grayscale image.

Parameters
[in]I: The image.
[in]tagsCorners: The vector of tag contours.
[out]color: The desired color, if none RGBY colors are used.
[out]thickness: The thickness of the lines.

Definition at line 1288 of file vpDetectorAprilTag.cpp.

◆ displayTags() [2/2]

void vpDetectorAprilTag::displayTags ( const vpImage< vpRGBa > & I,
const std::vector< std::vector< vpImagePoint > > & tagsCorners,
const vpColor & color = vpColor::none,
unsigned int thickness = 1 ) const

Display the tag contours on a vpRGBa image.

Parameters
[in]I: The image.
[in]tagsCorners: The vector of tag contours.
[out]color: The desired color, if none RGBY colors are used.
[out]thickness: The thickness of the lines.

Definition at line 1302 of file vpDetectorAprilTag.cpp.

◆ getAprilTagDecisionMarginThreshold()

float vpDetectorAprilTag::getAprilTagDecisionMarginThreshold ( ) const

Get the decision margin threshold to filter out false detections. Higher is the decision margin for each detected tag, better is the detection. When the decision margin threshold is equal to -1, tags decision margin values are not used to filter potential false positive detection.

See also
setAprilTagDecisionMarginThreshold(), setAprilTagHammingDistanceThreshold()
Examples
catchArUco.cpp.

Definition at line 1417 of file vpDetectorAprilTag.cpp.

◆ getAprilTagHammingDistanceThreshold()

int vpDetectorAprilTag::getAprilTagHammingDistanceThreshold ( ) const

Get the hamming distance threshold to filter out false detections. For each tag detected, the hamming distance is between 0 and 255 and indicates the number of bit-error that are corrected. A value of 0 indicates that no correction was applied when the tag was detected, while a value of 2 indicates that 2 bits were corrected to achieve detection. The lower the Hamming distance, the more reliable the detection.

Default value is 2, meaning that we don't filter out detections with corrected bits.

This threshold could be used to filter out detections where the hamming distance is greater than this threshold.

See also
setAprilTagHammingDistanceThreshold(), setAprilTagDecisionMarginThreshold()
Examples
catchArUco.cpp.

Definition at line 1435 of file vpDetectorAprilTag.cpp.

◆ getBBox()

vpRect vpDetectorBase::getBBox ( size_t i) const
inherited

◆ getCog()

vpImagePoint vpDetectorBase::getCog ( size_t i) const
inherited

Return the center of gravity location of the ith object.

Examples
servoBiclopsPoint2DArtVelocity.cpp, servoPololuPtuPoint2DJointVelocity.cpp, and tutorial-flir-ptu-ibvs.cpp.

Definition at line 78 of file vpDetectorBase.cpp.

References m_polygon.

Referenced by detect().

◆ getMessage() [1/2]

std::vector< std::string > & vpDetectorBase::getMessage ( )
inlineinherited

Returns the contained message of the ith object if there is one.

Examples
catchAprilTag.cpp, catchArUco.cpp, tutorial-barcode-detector-live.cpp, tutorial-barcode-detector.cpp, tutorial-face-detector-live.cpp, and tutorial-face-detector.cpp.

Definition at line 98 of file vpDetectorBase.h.

References m_message.

◆ getMessage() [2/2]

std::string & vpDetectorBase::getMessage ( size_t i)
inherited

Returns the contained message of the ith object if there is one.

Definition at line 64 of file vpDetectorBase.cpp.

References vpException::badValue, m_message, and m_polygon.

◆ getNbObjects()

◆ getPolygon() [1/2]

std::vector< std::vector< vpImagePoint > > & vpDetectorBase::getPolygon ( )
inlineinherited

Returns object container box as a vector of points.

Examples
catchAprilTag.cpp, tutorial-barcode-detector-live.cpp, tutorial-barcode-detector.cpp, and tutorial-pose-from-qrcode-image.cpp.

Definition at line 113 of file vpDetectorBase.h.

References m_polygon.

◆ getPolygon() [2/2]

std::vector< vpImagePoint > & vpDetectorBase::getPolygon ( size_t i)
inherited

Returns ith object container box as a vector of points.

Definition at line 50 of file vpDetectorBase.cpp.

References vpException::badValue, and m_polygon.

◆ getPose()

bool vpDetectorAprilTag::getPose ( size_t tagIndex,
double tagSize,
const vpCameraParameters & cam,
vpHomogeneousMatrix & cMo,
vpHomogeneousMatrix * cMo2 = nullptr,
double * projError = nullptr,
double * projError2 = nullptr )

Get the pose of a tag depending on its size and camera parameters. This function is useful to get the pose of tags with different sizes, while detect(const vpImage<unsigned char> &, const double, const vpCameraParameters &, std::vector<vpHomogeneousMatrix> &) considers that all the tags have the same size.

Parameters
[in]tagIndex: Index of the tag. Value should be in range [0, nb tags-1] with nb_tags = getNbObjects(). Note that this index doesn't correspond to the tag id.
[in]tagSize: Tag size in meter corresponding to the external width of the pattern.
[in]cam: Camera intrinsic parameters.
[out]cMo: Pose of the tag.
[out]cMo2: Optional second pose of the tag.
[out]projError: Optional (sum of squared) projection errors in the normalized camera frame.
[out]projError2: Optional (sum of squared) projection errors for the 2nd solution in the normalized camera frame.
Returns
true if success, false otherwise.

The following code shows how to use this function:

detector.detect(I);
for (size_t i = 0; i < detector.getNbObjects(); i++) {
double tagSize = 0.1;
detector.getPose(i, tagSize, cam, cMo);
}
See also
detect(const vpImage<unsigned char> &, double, const vpCameraParameters &, std::vector<vpHomogeneousMatrix> *, std::vector<vpHomogeneousMatrix> *, std::vector<double> *, std::vector<double> *)
Examples
catchAprilTag.cpp.

Definition at line 1339 of file vpDetectorAprilTag.cpp.

◆ getPoseEstimationMethod()

vpPoseEstimationMethod vpDetectorAprilTag::getPoseEstimationMethod ( ) const
inline

Return the pose estimation method.

Definition at line 390 of file vpDetectorAprilTag.h.

References getPoseEstimationMethod(), and m_poseEstimationMethod.

Referenced by getPoseEstimationMethod().

◆ getTagImage()

bool vpDetectorAprilTag::getTagImage ( vpImage< unsigned char > & I,
int id )

Create an image of a marker corresponding to the current tag family with a given id.

Parameters
[out]I: Image with the created marker.
[in]id: Marker id.
Returns
true when image created successfully, false otherwise.
Examples
catchArUco.cpp.

Definition at line 1474 of file vpDetectorAprilTag.cpp.

◆ getTagsCorners()

std::vector< std::vector< vpImagePoint > > vpDetectorAprilTag::getTagsCorners ( ) const

Return the corners coordinates for the detected tags.

See also
getTagsId(), getTagsPoints3D()
Examples
catchAprilTag.cpp.

Definition at line 1445 of file vpDetectorAprilTag.cpp.

References vpDetectorBase::m_polygon.

◆ getTagsDecisionMargin()

std::vector< float > vpDetectorAprilTag::getTagsDecisionMargin ( ) const

Return the decision marging for each detection. It could be seen as a quality detection indicator. The higher the value, the greater the confidence in detection.

Note
When the decision margin threshold set using setAprilTagDecisionMargin() differs from -1, this decision margin is used internally to filter out false detections.
See also
getTagsCorners(), getTagsPoints3D(), getTagsId(), getTagsHammingDistance(), setAprilTagDecisionMargin()
Examples
catchArUco.cpp.

Definition at line 1488 of file vpDetectorAprilTag.cpp.

◆ getTagsHammingDistance()

std::vector< int > vpDetectorAprilTag::getTagsHammingDistance ( ) const

Return the hamming distance for each detection in range 0 - 255. This hamming distance corresponds to the number of bits that were corrected. Having values greater than 0 leads to greatly increased false positive rates. Thus it could be seen as a quality detection indicator.

Note
As of this implementation, the detector cannot detect tags with a hamming distance greater than 2.
See also
getTagsCorners(), getTagsPoints3D(), getTagsId(), getTagsDecisionMargin()
Examples
catchArUco.cpp.

Definition at line 1500 of file vpDetectorAprilTag.cpp.

◆ getTagsId()

std::vector< int > vpDetectorAprilTag::getTagsId ( ) const

Return the decoded Apriltag id for each detection.

See also
getTagsCorners(), getTagsPoints3D(), getTagsDecisionMargin(), getTagsHammingDistance()
Examples
catchAprilTag.cpp, and catchArUco.cpp.

Definition at line 1507 of file vpDetectorAprilTag.cpp.

◆ getTagsPoints3D()

std::vector< std::vector< vpPoint > > vpDetectorAprilTag::getTagsPoints3D ( const std::vector< int > & tagsId,
const std::map< int, double > & tagsSize ) const

Return a vector that contains for each tag id the corresponding tag 3D corners coordinates in the tag frame.

Parameters
tagsId: A vector containing the id of each tag that is detected. It's size corresponds to the number of tags that are detected. This vector is returned by getTagsId().
tagsSize: a map that contains as first element a tag id and as second elements its 3D size in meter. When first element of this map is -1, the second element corresponds to the default tag size.
std::map<int, double> tagsSize;
tagsSize[-1] = 0.05; // Default tag size in meter, used when detected tag id is not in this map
tagsSize[10] = 0.1; // All tags with id 10 are 0.1 meter large
tagsSize[20] = 0.2; // All tags with id 20 are 0.2 meter large
See also
getTagsCorners(), getTagsId()
Examples
catchAprilTag.cpp.

Definition at line 1363 of file vpDetectorAprilTag.cpp.

References vpException::fatalError.

◆ isZAlignedWithCameraAxis()

bool vpDetectorAprilTag::isZAlignedWithCameraAxis ( ) const

Indicate it z-axis of the tag frame is aligned with the camera frame or not.

Returns
When true, z-axis are aligned, false otherwise

Definition at line 1696 of file vpDetectorAprilTag.cpp.

◆ operator=()

vpDetectorAprilTag & vpDetectorAprilTag::operator= ( vpDetectorAprilTag o)

Definition at line 1182 of file vpDetectorAprilTag.cpp.

References swap, and vpDetectorAprilTag().

◆ setAprilTagDebugOption()

void vpDetectorAprilTag::setAprilTagDebugOption ( bool flag)

Using this option allows debugging the AprilTag marker detection process. This can be used to understand why a marker is not detected for instance.

It will generate in the exe folder different debugging images, among others:

  • 'debug_preprocess.pnm' corresponding to 'decimation, sharp/blur' preprocessing
  • 'debug_threshold.pnm' corresponding to 'step 1. threshold the image, creating the edge image.'
  • 'debug_segmentation.pnm' corresponding to 'step 2. find connected components.'
  • 'debug_clusters.pnm' corresponding to the 'gradient_clusters()' function
  • 'debug_quads_raw.pnm' corresponding to the detected quad shapes
  • 'debug_samples.pnm' corresponding to the successfully decoded quad
  • 'debug_output.pnm' corresponding to the final output after post-processing (non-overlapping duplicate detections)
Parameters
[in]flag: Debug flag.

Definition at line 1462 of file vpDetectorAprilTag.cpp.

◆ setAprilTagDecisionMarginThreshold()

void vpDetectorAprilTag::setAprilTagDecisionMarginThreshold ( float decisionMarginThreshold)

See the AprilTag documentation:

A measure of the quality of the binary decoding process: the average difference between the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate better decodes. This is a reasonable measure of detection accuracy only for very small tags– not effective for larger tags (where we could have sampled anywhere within a bit cell and still gotten a good detection.)

It has been experimentally observed that using the AprilTag detection and decoding pipeline, lots of false positives arise with 16h5, 4x4, 5x5, 6x6 and 7x7 ArUco dictionnaries. A decision margin threshold can be used to filter these detections.

Parameters
[in]decisionMarginThreshold: Decision margin threshold used to filter false positive detections.
  • When this threshold is set to -1, the decision margin threshold is not used to eliminate detections whose detection margin is lower than this threshold.
  • When set, we recommand a value of 100 that makes especially 16h5, 4x4, 5x5, 6x6 and 7x7 ArUco families detection more reliable.
  • Default value is set to -1.
See also
getAprilTagDecisionMarginThreshold(), getTagsDecisionMargin()
Examples
catchArUco.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, and tutorial-mb-generic-tracker-apriltag-webcam.cpp.

Definition at line 1537 of file vpDetectorAprilTag.cpp.

◆ setAprilTagDecodeSharpening()

void vpDetectorAprilTag::setAprilTagDecodeSharpening ( double decodeSharpening)

Definition at line 1509 of file vpDetectorAprilTag.cpp.

◆ setAprilTagFamily()

void vpDetectorAprilTag::setAprilTagFamily ( const vpAprilTagFamily & tagFamily)

Definition at line 1569 of file vpDetectorAprilTag.cpp.

References m_poseEstimationMethod.

◆ setAprilTagHammingDistanceThreshold()

void vpDetectorAprilTag::setAprilTagHammingDistanceThreshold ( int hammingDistanceThreshold)

See the AprilTag documentation:

How many error bits were corrected? Note: accepting large numbers of corrected errors leads to greatly increased false positive rates. NOTE: As of this implementation, the detector cannot detect tags with a hamming distance greater than 2.

It has been experimentally observed that using the AprilTag detection and decoding pipeline, lots of false positives arise with 16h5, 4x4, 5x5, 6x6 and 7x7 ArUco dictionnaries. Their hamming distance is than usually set to 2. A hamming distance threshold can be used to filter these detections using setAprilTagHammingDistanceThreshold().

Parameters
[in]hammingDistanceThreshold: Threshold between 0 and 255 used to filter tags whose hamming distance is greater than this threshold.
  • When this threshold is set to 0, only tags for which no bits are corrected are detected.
  • When set to 2, it means that we keep all the tags that have up to 2 corrected bits. It will lead to false positive detections.
  • Default value is set to 2.
See also
getAprilTagDecisionMarginThreshold(), getTagsDecisionMargin()
Examples
catchArUco.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, and tutorial-mb-generic-tracker-apriltag-webcam.cpp.

Definition at line 1563 of file vpDetectorAprilTag.cpp.

◆ setAprilTagNbThreads()

void vpDetectorAprilTag::setAprilTagNbThreads ( int nThreads)

Set the number of threads for April Tag detection (default is 1).

Parameters
nThreads: Number of thread.
Examples
perfApriltagDetection.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, and tutorial-mb-generic-tracker-apriltag-webcam.cpp.

Definition at line 1599 of file vpDetectorAprilTag.cpp.

◆ setAprilTagPoseEstimationMethod()

void vpDetectorAprilTag::setAprilTagPoseEstimationMethod ( const vpPoseEstimationMethod & poseEstimationMethod)

Set the method to use to compute the pose,

See also
vpPoseEstimationMethod
Parameters
poseEstimationMethod: The method to used.
Examples
tutorial-flir-ptu-ibvs.cpp.

Definition at line 1611 of file vpDetectorAprilTag.cpp.

References m_poseEstimationMethod.

◆ setAprilTagQuadDecimate()

void vpDetectorAprilTag::setAprilTagQuadDecimate ( float quadDecimate)

From the AprilTag code:

detection of quads can be done on a lower-resolution image, improving speed at a cost of pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still done at full resolution.

Default is 1.0, increase this value to reduce the computation time.

Parameters
quadDecimate: Value for quad_decimate.
Examples
catchAprilTag.cpp, perfApriltagDetection.cpp, tutorial-flir-ptu-ibvs.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, and tutorial-mb-generic-tracker-apriltag-webcam.cpp.

Definition at line 1629 of file vpDetectorAprilTag.cpp.

◆ setAprilTagQuadSigma()

void vpDetectorAprilTag::setAprilTagQuadSigma ( float quadSigma)

From the AprilTag code:

What Gaussian blur should be applied to the segmented image (used for quad detection?) Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values (e.g. 0.8).

Default is 0.0.

Parameters
quadSigma: Value for quad_sigma.
Examples
perfApriltagDetection.cpp.

Definition at line 1643 of file vpDetectorAprilTag.cpp.

◆ setAprilTagRefineDecode()

void vpDetectorAprilTag::setAprilTagRefineDecode ( bool refineDecode)
Deprecated
Deprecated parameter from AprilTag 2 version.

Definition at line 1649 of file vpDetectorAprilTag.cpp.

◆ setAprilTagRefineEdges()

void vpDetectorAprilTag::setAprilTagRefineEdges ( bool refineEdges)

From the AprilTag code:

When non-zero, the edges of the each quad are adjusted to "snap to" strong gradients nearby. This is useful when decimation is employed, as it can increase the quality of the initial quad estimate substantially. Generally recommended to be on (1). Very computationally inexpensive. Option is ignored if quad_decimate = 1.

Default is 1.

Parameters
refineEdges: If true, set refine edges parameter.

Definition at line 1669 of file vpDetectorAprilTag.cpp.

◆ setAprilTagRefinePose()

void vpDetectorAprilTag::setAprilTagRefinePose ( bool refinePose)
Deprecated
Deprecated parameter from AprilTag 2 version.

Definition at line 1675 of file vpDetectorAprilTag.cpp.

◆ setDisplayTag()

void vpDetectorAprilTag::setDisplayTag ( bool display,
const vpColor & color = vpColor::none,
unsigned int thickness = 2 )
inline

Allow to enable the display of overlay tag information in the windows (vpDisplay) associated to the input image.

Examples
tutorial-flir-ptu-ibvs.cpp.

Definition at line 416 of file vpDetectorAprilTag.h.

References m_displayTag, m_displayTagColor, m_displayTagThickness, and vpColor::none.

◆ setTimeout()

void vpDetectorBase::setTimeout ( unsigned long timeout_ms)
inlineinherited

Set detector timeout in milli-seconds. When set to 0, there is no timeout.

Definition at line 123 of file vpDetectorBase.h.

References m_timeout_ms.

Referenced by vpDetectorDataMatrixCode::vpDetectorDataMatrixCode().

◆ setZAlignedWithCameraAxis()

void vpDetectorAprilTag::setZAlignedWithCameraAxis ( bool zAlignedWithCameraFrame)

Modify the resulting tag pose returned by getPose() or detect(const vpImage<unsigned char> &, double, const vpCameraParameters &, std::vector<vpHomogeneousMatrix> &, std::vector<vpHomogeneousMatrix> *, std::vector<double> *, std::vector<double> *) in order to get a pose where z-axis is aligned when the camera plane is parallel to the tag.

Tag 36h11_00000 with location of the 4 corners and tag frame
Parameters
zAlignedWithCameraFrame: When set to true, estimated tag pose has a z-axis aligned with the camera frame.

Definition at line 1687 of file vpDetectorAprilTag.cpp.

◆ swap

void swap ( vpDetectorAprilTag & o1,
vpDetectorAprilTag & o2 )
friend

Definition at line 423 of file vpDetectorAprilTag.h.

References swap, and vpDetectorAprilTag().

Referenced by operator=(), and swap.

Member Data Documentation

◆ m_displayTag

bool vpDetectorAprilTag::m_displayTag
protected

◆ m_displayTagColor

vpColor vpDetectorAprilTag::m_displayTagColor
protected

◆ m_displayTagThickness

unsigned int vpDetectorAprilTag::m_displayTagThickness
protected

◆ m_message

std::vector<std::string> vpDetectorBase::m_message
protectedinherited

◆ m_nb_objects

size_t vpDetectorBase::m_nb_objects
protectedinherited

◆ m_polygon

std::vector<std::vector<vpImagePoint> > vpDetectorBase::m_polygon
protectedinherited

◆ m_poseEstimationMethod

vpPoseEstimationMethod vpDetectorAprilTag::m_poseEstimationMethod
protected

◆ m_tagFamily

vpAprilTagFamily vpDetectorAprilTag::m_tagFamily
protected

Definition at line 446 of file vpDetectorAprilTag.h.

Referenced by vpDetectorAprilTag(), and vpDetectorAprilTag().

◆ m_timeout_ms

unsigned long vpDetectorBase::m_timeout_ms
protectedinherited

Detection timeout.

Definition at line 131 of file vpDetectorBase.h.

Referenced by vpDetectorDataMatrixCode::detect(), setTimeout(), vpDetectorBase(), and vpDetectorBase().