Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
aruco Namespace Reference

Namespaces

 aruco_private
 

Classes

class  CameraParameters
 Parameters of the camera. More...
 
class  CvDrawingUtils
 A set of functions to draw in opencv images. More...
 
class  Debug
 
class  Dictionary
 
class  DictionaryBased
 
class  FractalDetector
 
class  FractalMarker
 
class  FractalMarkerLabeler
 
class  FractalMarkerSet
 
class  FractalPoseTracker
 
class  LevMarq
 
class  Marker
 
class  Marker3DInfo
 
class  MarkerDetector
 Main class for marker detection. More...
 
class  MarkerDetector_Impl
 Main class for marker detection. More...
 
class  MarkerLabeler
 
class  MarkerMap
 This class defines a set of markers whose locations are attached to a common reference system, i.e., they do not move wrt each other. A MarkerMap contains several markers so that they are more robustly detected. More...
 
class  MarkerMapPoseTracker
 
class  MarkerPoseTracker
 
struct  PicoFlann_KeyPointAdapter
 
struct  ScopedTimerEvents
 
struct  ScopeTimer
 
struct  Timer
 

Typedefs

typedef Marker MarkerCandidate
 

Enumerations

enum  CornerRefinementMethod : int { CORNER_SUBPIX = 0, CORNER_LINES = 1, CORNER_NONE = 2 }
 
enum  DetectionMode : int { DM_NORMAL = 0, DM_FAST = 1, DM_VIDEO_FAST = 2 }
 The DetectionMode enum defines the different possibilities for detection. 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: More...
 

Functions

template<typename T >
double __aruco_solve_pnp (const std::vector< cv::Point3f > &p3d, const std::vector< cv::Point2f > &p2d, const cv::Mat &cam_matrix, const cv::Mat &dist, cv::Mat &r_io, cv::Mat &t_io)
 
void __glGetModelViewMatrix (double modelview_matrix[16], const cv::Mat &Rvec, const cv::Mat &Tvec)
 
void __OgreGetPoseParameters (double position[3], double orientation[4], const cv::Mat &Rvec, const cv::Mat &Tvec)
 
std::string __pf_aruco_methodName (std::string prettyFunction)
 
void assignClass (const cv::Mat &im, std::vector< cv::KeyPoint > &kpoints, float sizeNorm=0.f, int wsize=5)
 assignClass More...
 
double getHubberMonoWeight (double SqErr, double Information)
 
cv::Mat getRTMatrix (const cv::Mat &R_, const cv::Mat &T_, int forceType)
 
int hamm_distance (uint64_t a, uint64_t b)
 
double hubber (double e, double _delta)
 
double hubberMono (double e)
 
void impl_assignClass_fast (const cv::Mat &im, std::vector< cv::KeyPoint > &kpoints, bool norm, int wsize)
 
void kcornerSubPix (const cv::Mat image, std::vector< cv::KeyPoint > &kpoints)
 
void kfilter (std::vector< cv::KeyPoint > &kpoints)
 
std::ostream & operator<< (std::ostream &str, const CameraParameters &cp)
 
std::istream & operator>> (std::istream &str, CameraParameters &cp)
 
void print (cv::Point3f p, std::string cad)
 
std::vector< cv::Mat > solvePnP (const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
 
void solvePnP (const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs, cv::Mat &rvec, cv::Mat &tvec)
 
vector< cv::Mat > solvePnP (const vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
 
void solvePnP (const vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs, cv::Mat &rvec, cv::Mat &tvec)
 
std::vector< std::pair< cv::Mat, double > > solvePnP_ (const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
 
ARUCO_EXPORT std::vector< std::pair< cv::Mat, double > > solvePnP_ (float size, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
 

Variables

auto rotate
 

Detailed Description

Copyright 2020 Rafael Muñoz Salinas. All rights reserved.

This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation version 3 of the License.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see https://www.gnu.org/licenses/.

Copyright 2017 Rafael Muñoz Salinas. All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

The views and conclusions contained in the software and documentation are those of the authors and should not be interpreted as representing official policies, either expressed or implied, of Rafael Muñoz Salinas.

Typedef Documentation

◆ MarkerCandidate

Definition at line 84 of file markerdetector.h.

Enumeration Type Documentation

◆ CornerRefinementMethod

Method employed to refine the estimation of the corners

  • CORNER_SUBPIX: uses subpixel refinement implemented in opencv
  • CORNER_LINES: uses all the pixels in the corner border to estimate the 4 lines of the square. Then estimate the point in which they intersect. In seems that it more robust to noise. However, it only works if input image is not resized. So, the value minMarkerSize will be set to 0.
  • CORNER_NONE: Does no refinement of the corner. Again, it requires minMakerSize to be 0
Enumerator
CORNER_SUBPIX 
CORNER_LINES 
CORNER_NONE 

Definition at line 74 of file markerdetector.h.

◆ DetectionMode

The DetectionMode enum defines the different possibilities for detection. 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.
Enumerator
DM_NORMAL 
DM_FAST 
DM_VIDEO_FAST 

Definition at line 60 of file markerdetector.h.

Function Documentation

◆ __aruco_solve_pnp()

template<typename T >
double aruco::__aruco_solve_pnp ( const std::vector< cv::Point3f > &  p3d,
const std::vector< cv::Point2f > &  p2d,
const cv::Mat &  cam_matrix,
const cv::Mat &  dist,
cv::Mat &  r_io,
cv::Mat &  t_io 
)

Definition at line 288 of file posetracker.cpp.

◆ __glGetModelViewMatrix()

void aruco::__glGetModelViewMatrix ( double  modelview_matrix[16],
const cv::Mat &  Rvec,
const cv::Mat &  Tvec 
)

Definition at line 162 of file markermap.cpp.

◆ __OgreGetPoseParameters()

void aruco::__OgreGetPoseParameters ( double  position[3],
double  orientation[4],
const cv::Mat &  Rvec,
const cv::Mat &  Tvec 
)

Definition at line 219 of file markermap.cpp.

◆ __pf_aruco_methodName()

std::string aruco::__pf_aruco_methodName ( std::string  prettyFunction)
inline

Definition at line 261 of file timers.h.

◆ assignClass()

void aruco::assignClass ( const cv::Mat &  im,
std::vector< cv::KeyPoint > &  kpoints,
float  sizeNorm = 0.f,
int  wsize = 5 
)

assignClass

classification of the corners

Parameters
imimage used in the classification
kpointsto classify
sizeNorm.Is it necessary to transform keypoints? When keypoints have as reference the center of image(0,0), it is necessary to provide the fractal marker size
wsize.Window size

Definition at line 82 of file fractalposetracker.cpp.

◆ getHubberMonoWeight()

double aruco::getHubberMonoWeight ( double  SqErr,
double  Information 
)
inline

Definition at line 283 of file posetracker.cpp.

◆ getRTMatrix()

cv::Mat aruco::getRTMatrix ( const cv::Mat &  R_,
const cv::Mat &  T_,
int  forceType 
)

Definition at line 33 of file ippe.cpp.

◆ hamm_distance()

int aruco::hamm_distance ( uint64_t  a,
uint64_t  b 
)

Definition at line 76 of file dictionary_based.cpp.

◆ hubber()

double aruco::hubber ( double  e,
double  _delta 
)
inline

Definition at line 255 of file posetracker.cpp.

◆ hubberMono()

double aruco::hubberMono ( double  e)
inline

Definition at line 271 of file posetracker.cpp.

◆ impl_assignClass_fast()

void aruco::impl_assignClass_fast ( const cv::Mat &  im,
std::vector< cv::KeyPoint > &  kpoints,
bool  norm,
int  wsize 
)

Definition at line 198 of file markerdetector_impl.cpp.

◆ kcornerSubPix()

void aruco::kcornerSubPix ( const cv::Mat  image,
std::vector< cv::KeyPoint > &  kpoints 
)

Definition at line 17 of file fractalposetracker.cpp.

◆ kfilter()

void aruco::kfilter ( std::vector< cv::KeyPoint > &  kpoints)

Definition at line 40 of file fractalposetracker.cpp.

◆ operator<<()

std::ostream& aruco::operator<< ( std::ostream &  str,
const CameraParameters cp 
)

Definition at line 528 of file cameraparameters.cpp.

◆ operator>>()

std::istream& aruco::operator>> ( std::istream &  str,
CameraParameters cp 
)

Definition at line 541 of file cameraparameters.cpp.

◆ print()

void aruco::print ( cv::Point3f  p,
std::string  cad 
)

Definition at line 310 of file marker.cpp.

◆ solvePnP() [1/4]

std::vector<cv::Mat> aruco::solvePnP ( const std::vector< cv::Point3f > &  objPoints,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs 
)

Definition at line 88 of file ippe.cpp.

◆ solvePnP() [2/4]

void aruco::solvePnP ( const std::vector< cv::Point3f > &  objPoints,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs,
cv::Mat &  rvec,
cv::Mat &  tvec 
)

Definition at line 103 of file ippe.cpp.

◆ solvePnP() [3/4]

vector<cv::Mat> aruco::solvePnP ( const vector< cv::Point3f > &  objPoints,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs 
)

Definition at line 88 of file ippe.cpp.

◆ solvePnP() [4/4]

void aruco::solvePnP ( const vector< cv::Point3f > &  objPoints,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs,
cv::Mat &  rvec,
cv::Mat &  tvec 
)

Definition at line 103 of file ippe.cpp.

◆ solvePnP_() [1/2]

std::vector< std::pair< cv::Mat, double > > aruco::solvePnP_ ( const std::vector< cv::Point3f > &  objPoints,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs 
)

Definition at line 132 of file ippe.cpp.

◆ solvePnP_() [2/2]

std::vector< std::pair< cv::Mat, double > > aruco::solvePnP_ ( float  size,
const std::vector< cv::Point2f > &  imgPoints,
cv::InputArray  cameraMatrix,
cv::InputArray  distCoeffs 
)

Definition at line 115 of file ippe.cpp.

Variable Documentation

◆ rotate

auto aruco::rotate
Initial value:
= [](const cv::Mat &m)
{
cv::Mat out;
m.copyTo(out);
for (int i = 0; i < m.rows; i++)
{
for (int j = 0; j < m.cols; j++)
{
out.at<char>(i, j) = m.at<char>(m.cols - j - 1, i);
}
}
return out;
}

Definition at line 526 of file fractalmarkerset.cpp.



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