fractaldetector.h
Go to the documentation of this file.
1 
17 #ifndef _ARUCO_FractalDetector_H
18 #define _ARUCO_FractalDetector_H
19 
20 #include "markerdetector.h"
22 #include "aruco_export.h"
23 namespace aruco
24 {
26 {
28  {
29  std::string configuration_type;
30  };
31 
32 public:
34 
39  void setConfiguration(int configuration);
40 
45  void setConfiguration(std::string configuration);
46 
52  void setParams(const CameraParameters &cam_params, float markerSize)
53  {
54  _cam_params = cam_params;
55 
56  Tracker.setParams(cam_params, _fractalLabeler->_fractalMarkerSet, markerSize);
57  }
58 
59  // return fractalmarkerset
61  {
62  return Tracker.getFractal();
63  }
64 
65  // return true if any marker is detected, false otherwise
66  bool detect(const cv::Mat &input)
67  {
68  Markers = _markerDetector->detect(input);
69 
70  if (Markers.size() > 0)
71  return true;
72  else
73  return false;
74  }
75 
76  // return true if the pose is estimated, false otherwise
78  {
79  if (_cam_params.isValid())
80  {
81  return Tracker.fractalInnerPose(_markerDetector, Markers);
82  }
83  else
84  return false;
85  }
86 
87  // return the rotation vector. Returns an empty matrix if last call to estimatePose returned false
88  cv::Mat getRvec()
89  {
90  return Tracker.getRvec();
91  }
92  // return the translation vector. Returns an empty matrix if last call to estimatePose returned false
93  cv::Mat getTvec()
94  {
95  return Tracker.getTvec();
96  }
97 
98  void drawImage(cv::Mat &img, cv::Mat &img2);
99 
100  // draw borders of markers
101  void drawMarkers(cv::Mat &img);
102 
103  // draw inner corners of markers
104  void draw2d(cv::Mat &img);
105 
106  // draw pose estimation axes
107  void draw3d(cv::Mat &img, bool cube = true, bool axis = true);
108 
109  // draw marker as cube
110  void draw3dCube(cv::Mat &Image, FractalMarker m, const CameraParameters &CP, int lineSize);
111 
112  // return detected markers
113  std::vector<Marker> getMarkers()
114  {
115  return Markers;
116  }
117 
118  // return image pyramid
119  std::vector<cv::Mat> getImagePyramid()
120  {
121  return _markerDetector->getImagePyramid();
122  }
123 
124 private:
125  std::vector<aruco::Marker> Markers; // detected markers
128  CameraParameters _cam_params; // Camera parameters
129  cv::Ptr<FractalMarkerLabeler> _fractalLabeler;
130  cv::Ptr<MarkerDetector> _markerDetector;
131 };
132 } // namespace aruco
133 #endif
cv::Ptr< FractalMarkerLabeler > _fractalLabeler
cv::Ptr< MarkerDetector > _markerDetector
FractalMarkerSet getConfiguration()
Parameters of the camera.
void setParams(cv::Mat cameraMatrix, cv::Mat distorsionCoeff, cv::Size size)
std::vector< Marker > getMarkers()
CameraParameters _cam_params
void setParams(const CameraParameters &cam_params, float markerSize)
setParams
#define ARUCO_EXPORT
Definition: aruco_export.h:30
std::vector< aruco::Marker > Markers
FractalPoseTracker Tracker
bool detect(const cv::Mat &input)
std::vector< cv::Mat > getImagePyramid()


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Fri Nov 25 2022 04:02:23