Main Page
Namespaces
Classes
Files
File List
File Members
include
marker_detection.h
Go to the documentation of this file.
1
18
#ifndef MARKER_DETECTION_H
19
#define MARKER_DETECTION_H
20
21
#include "
aruco/aruco.h
"
22
#include <geometry_msgs/Pose.h>
23
#include <sensor_msgs/CameraInfo.h>
24
#include <asr_aruco_marker_recognition/ArucoMarkerRecognitionConfig.h>
25
26
namespace
aruco_marker_recognition
{
27
28
using namespace
asr_aruco_marker_recognition
;
29
33
class
MarkerDetection
{
34
35
36
private
:
37
39
double
DEFAULT_MARKER_SIZE
= 0.1;
40
42
double
marker_size_
;
43
45
aruco::CameraParameters
cam_params_left_
;
46
48
aruco::CameraParameters
cam_params_right_
;
49
50
51
public
:
53
enum
CameraId
{ cam_left, cam_right };
54
58
MarkerDetection
() :
MarkerDetection
(DEFAULT_MARKER_SIZE) {}
59
64
MarkerDetection
(
double
marker_size);
65
72
std::vector<aruco::Marker> detect(
const
cv::Mat &image,
CameraId
id
,
const
ArucoMarkerRecognitionConfig &config);
73
79
void
setCameraParameters(
const
sensor_msgs::CameraInfo &cam_params_left,
const
sensor_msgs::CameraInfo &cam_params_right);
80
};
81
82
}
83
84
85
#endif
86
87
aruco_marker_recognition::MarkerDetection::marker_size_
double marker_size_
Definition:
marker_detection.h:42
aruco_marker_recognition
Definition:
aruco_marker_recognition.h:39
aruco_marker_recognition::MarkerDetection
This class is used to detect markers in an image using the aruco-library.
Definition:
marker_detection.h:33
aruco_marker_recognition::MarkerDetection::CameraId
CameraId
Definition:
marker_detection.h:53
aruco.h
aruco_marker_recognition::MarkerDetection::MarkerDetection
MarkerDetection()
The default constructor of this class.
Definition:
marker_detection.h:58
aruco_marker_recognition::MarkerDetection::cam_params_left_
aruco::CameraParameters cam_params_left_
Definition:
marker_detection.h:45
aruco_marker_recognition::MarkerDetection::cam_params_right_
aruco::CameraParameters cam_params_right_
Definition:
marker_detection.h:48
aruco::CameraParameters
Parameters of the camera.
Definition:
cameraparameters.h:38
asr_aruco_marker_recognition
aruco_marker_recognition::DEFAULT_MARKER_SIZE
static const double DEFAULT_MARKER_SIZE(0.05)
asr_aruco_marker_recognition
Author(s): Allgeyer Tobias, Meißner Pascal, Qattan Mohamad
autogenerated on Mon Jun 10 2019 12:40:21