Public Types | Public Member Functions | Private Attributes
aruco_marker_recognition::MarkerDetection Class Reference

This class is used to detect markers in an image using the aruco-library. More...

#include <marker_detection.h>

List of all members.

Public Types

enum  CameraId { cam_left, cam_right }

Public Member Functions

std::vector< aruco::Markerdetect (const cv::Mat &image, CameraId id, const ArucoMarkerRecognitionConfig &config)
 Detects markers in the given image with the camera parameters of the camera with the given id.
 MarkerDetection ()
 The default constructor of this class.
 MarkerDetection (double marker_size)
 The constructor of this class.
void setCameraParameters (const sensor_msgs::CameraInfo &cam_params_left, const sensor_msgs::CameraInfo &cam_params_right)
 Set the camera parameters of the two cameras.

Private Attributes

aruco::CameraParameters cam_params_left_
aruco::CameraParameters cam_params_right_
double DEFAULT_MARKER_SIZE = 0.1
double marker_size_

Detailed Description

This class is used to detect markers in an image using the aruco-library.

Definition at line 33 of file marker_detection.h.


Member Enumeration Documentation

An enum describing the ids of the two cameras

Enumerator:
cam_left 
cam_right 

Definition at line 53 of file marker_detection.h.


Constructor & Destructor Documentation

The default constructor of this class.

Definition at line 58 of file marker_detection.h.

The constructor of this class.

Parameters:
marker_sizeThe size of the used markers in meters

Definition at line 26 of file marker_detection.cpp.


Member Function Documentation

std::vector< aruco::Marker > aruco_marker_recognition::MarkerDetection::detect ( const cv::Mat &  image,
CameraId  id,
const ArucoMarkerRecognitionConfig &  config 
)

Detects markers in the given image with the camera parameters of the camera with the given id.

Parameters:
imageThe image the markers are detected in
idThe id of the camera the given image was fetched from (specified in the enum CameraId)
Returns:
A list containing the detected markers

Definition at line 30 of file marker_detection.cpp.

void aruco_marker_recognition::MarkerDetection::setCameraParameters ( const sensor_msgs::CameraInfo &  cam_params_left,
const sensor_msgs::CameraInfo &  cam_params_right 
)

Set the camera parameters of the two cameras.

Parameters:
cam_params_leftThe parameters of the left camera
cam_params_rightThe parameters of the right camera

Definition at line 73 of file marker_detection.cpp.


Member Data Documentation

The camera parameters of the left camera

Definition at line 45 of file marker_detection.h.

The camera parameters of the right camera

Definition at line 48 of file marker_detection.h.

The default marker size in meters

Definition at line 39 of file marker_detection.h.

The custom marker size in meters

Definition at line 42 of file marker_detection.h.


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


asr_aruco_marker_recognition
Author(s): Allgeyer Tobias, Meißner Pascal, Qattan Mohamad
autogenerated on Thu Jun 6 2019 21:14:12