JeVoisBase  1.21
JeVois Smart Embedded Machine Vision Toolkit Base Modules
Share this page:
Loading...
Searching...
No Matches
ArUco Class Reference

Simple wrapper class over the opencv_contrib ArUco augmented reality markers. More...

#include <jevoisbase/Components/ArUco/ArUco.H>

Inheritance diagram for ArUco:
Collaboration diagram for ArUco:

Public Member Functions

virtual ~ArUco ()
 Destructor.
 
void postInit () override
 Initialize, create the detector and read the config files.
 
void postUninit () override
 Un-initialize, nuke allocated resources.
 
void detectMarkers (cv::InputArray image, cv::OutputArray ids, cv::OutputArrayOfArrays corners)
 Detect markers.
 
void estimatePoseSingleMarkers (cv::InputArrayOfArrays corners, cv::OutputArray rvecs, cv::OutputArray tvecs)
 Estimate pose of individual markers.
 
void drawDetections (jevois::RawImage &outimg, int txtx, int txty, std::vector< int > ids, std::vector< std::vector< cv::Point2f > > corners, std::vector< cv::Vec3d > const &rvecs, std::vector< cv::Vec3d > const &tvecs)
 Draw any markers previously detected by detectMarkers()
 
void drawDetections (jevois::GUIhelper &helper, std::vector< int > ids, std::vector< std::vector< cv::Point2f > > corners, std::vector< cv::Vec3d > const &rvecs, std::vector< cv::Vec3d > const &tvecs)
 Draw any markers previously detected by detectMarkers()
 
void sendSerial (jevois::StdModule *mod, std::vector< int > ids, std::vector< std::vector< cv::Point2f > > corners, unsigned int w, unsigned int h, std::vector< cv::Vec3d > const &rvecs, std::vector< cv::Vec3d > const &tvecs)
 Send serial messages about detections.
 
- Public Member Functions inherited from jevois::Component
 Component (std::string const &instance)
 
virtual ~Component ()
 
std::shared_ptr< Comp > addSubComponent (std::string const &instance, Args &&...args)
 
void removeSubComponent (std::shared_ptr< Comp > &component)
 
void removeSubComponent (std::string const &instance, bool warnIfNotFound=true)
 
std::shared_ptr< Comp > getSubComponent (std::string const &instance) const
 
bool isTopLevel () const
 
bool initialized () const
 
std::string const & className () const
 
std::string const & instanceName () const
 
std::vector< std::string > setParamVal (std::string const &paramdescriptor, T const &val)
 
void setParamValUnique (std::string const &paramdescriptor, T const &val)
 
std::vector< std::pair< std::string, T > > getParamVal (std::string const &paramdescriptor) const
 
getParamValUnique (std::string const &paramdescriptor) const
 
std::vector< std::string > setParamString (std::string const &paramdescriptor, std::string const &val)
 
void setParamStringUnique (std::string const &paramdescriptor, std::string const &val)
 
std::vector< std::pair< std::string, std::string > > getParamString (std::string const &paramdescriptor) const
 
std::string getParamStringUnique (std::string const &paramdescriptor) const
 
void freezeParam (std::string const &paramdescriptor, bool doit)
 
void freezeAllParams (bool doit)
 
std::string descriptor () const
 
void setParamsFromFile (std::string const &filename)
 
std::istream & setParamsFromStream (std::istream &is, std::string const &absfile)
 
virtual void paramInfo (std::shared_ptr< UserInterface > s, std::map< std::string, std::string > &categs, bool skipFrozen, std::string const &cname="", std::string const &pfx="")
 
void foreachParam (std::function< void(std::string const &compname, ParameterBase *p)> func, std::string const &cname="")
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ParameterCategory const &category)
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ValidValuesSpec< T > const &validValuesSpec, ParameterCategory const &category)
 
void setDynamicParameterCallback (std::string const &name, std::function< void(T const &)> cb, bool callnow=true)
 
void removeDynamicParameter (std::string const &name, bool throw_if_not_found=true)
 
void setPath (std::string const &path)
 
std::filesystem::path absolutePath (std::filesystem::path const &path="")
 
std::shared_ptr< Comp > addSubComponent (std::string const &instance, Args &&...args)
 
void removeSubComponent (std::shared_ptr< Comp > &component)
 
void removeSubComponent (std::string const &instance, bool warnIfNotFound=true)
 
std::shared_ptr< Comp > getSubComponent (std::string const &instance) const
 
bool isTopLevel () const
 
bool initialized () const
 
std::string const & className () const
 
std::string const & instanceName () const
 
std::vector< std::string > setParamVal (std::string const &paramdescriptor, T const &val)
 
void setParamValUnique (std::string const &paramdescriptor, T const &val)
 
std::vector< std::pair< std::string, T > > getParamVal (std::string const &paramdescriptor) const
 
getParamValUnique (std::string const &paramdescriptor) const
 
std::vector< std::string > setParamString (std::string const &paramdescriptor, std::string const &val)
 
void setParamStringUnique (std::string const &paramdescriptor, std::string const &val)
 
std::vector< std::pair< std::string, std::string > > getParamString (std::string const &paramdescriptor) const
 
std::string getParamStringUnique (std::string const &paramdescriptor) const
 
void freezeParam (std::string const &paramdescriptor, bool doit)
 
void freezeAllParams (bool doit)
 
std::string descriptor () const
 
void setParamsFromFile (std::string const &filename)
 
std::istream & setParamsFromStream (std::istream &is, std::string const &absfile)
 
virtual void paramInfo (std::shared_ptr< UserInterface > s, std::map< std::string, std::string > &categs, bool skipFrozen, std::string const &cname="", std::string const &pfx="")
 
void foreachParam (std::function< void(std::string const &compname, ParameterBase *p)> func, std::string const &cname="")
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ParameterCategory const &category)
 
std::shared_ptr< DynamicParameter< T > > addDynamicParameter (std::string const &name, std::string const &description, T const &defaultValue, ValidValuesSpec< T > const &validValuesSpec, ParameterCategory const &category)
 
void setDynamicParameterCallback (std::string const &name, std::function< void(T const &)> cb, bool callnow=true)
 
void removeDynamicParameter (std::string const &name, bool throw_if_not_found=true)
 
void setPath (std::string const &path)
 
std::filesystem::path absolutePath (std::filesystem::path const &path="")
 
- Public Member Functions inherited from jevois::ParameterRegistry
virtual ~ParameterRegistry ()
 

Static Public Member Functions

static cv::aruco::Dictionary getDictionary (aruco::Dict d)
 Static method to allow anyone to get the ArUco dictionary for a given value of our dictionary parameter.
 

Protected Attributes

cv::Ptr< cv::aruco::ArucoDetector > itsDetector
 
jevois::CameraCalibration itsCalib
 

Related Symbols

(Note that these are not member symbols.)

 JEVOIS_DECLARE_PARAMETER (detparams, std::string, "Filename of detector parameters, or empty - Note that " "this parameter cannot be changed at runtime (must be set in the module's params.cfg).", "", ParamCateg)
 Parameter.
 
 JEVOIS_DEFINE_ENUM_CLASS (Dict,(Original)(D4X4_50)(D4X4_100)(D4X4_250)(D4X4_1000)(D5X5_50)(D5X5_100)(D5X5_250)(D5X5_1000)(D6X6_50)(D6X6_100)(D6X6_250)(D6X6_1000)(D7X7_50)(D7X7_100)(D7X7_250)(D7X7_1000)(ATAG_16h5)(ATAG_25h9)(ATAG_36h10)(ATAG_36h11))
 Enum for parameter.
 
 JEVOIS_DECLARE_PARAMETER (dictionary, Dict, "Symbol dictionary to use - Note that " "this parameter cannot be changed at runtime (must be set in the module's params.cfg).", Dict::D4X4_50, Dict_Values, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER (dopose, bool, "Compute (and show) pose vectors, requires a valid camera calibration", false, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER (markerlen, float, "Marker side length (millimeters), used only for pose estimation", 100.0F, ParamCateg)
 Parameter.
 
 JEVOIS_DECLARE_PARAMETER (showcube, bool, "Show a 3D cube on top of each detected marker, when dopose is also true", false, aruco::ParamCateg)
 Parameter.
 

Additional Inherited Members

- Protected Member Functions inherited from jevois::Component
virtual void preInit ()
 
virtual void preUninit ()
 
virtual void preInit ()
 
virtual void preUninit ()
 
- Protected Member Functions inherited from jevois::ParameterRegistry
void addParameter (ParameterBase *const param)
 
void removeParameter (ParameterBase *const param)
 
void callbackInitCall ()
 

Detailed Description

Simple wrapper class over the opencv_contrib ArUco augmented reality markers.

ArUco markers are small 2D barcodes. Each ArUco marker corresponds to a number, encoded into a small grid of black and white pixels. The ArUco decoding algorithm is capable of locating, decoding, and of estimating the pose (location and orientation in space) of any ArUco markers in the camera's field of view.

ArUcos are very useful as tags for many robotics and augmented reality applications. For example, one may place an ArUco next to a robot's charging station, an elevator button, or an object that a robot should manipulate.

For more information about ArUco, see https://www.uco.es/investiga/grupos/ava/node/26

The implementation of ArUco used by JeVois is the one of OpenCV-Contrib, documented here: http://docs.opencv.org/3.2.0/d5/dae/tutorial_aruco_detection.html

ArUco markers can be created with several standard dictionaries. Different disctionaries give rise to different numbers of pixels in the markers, and to different numbers of possible symbols that can be created using the dictionary. The default dictionary used by JeVois is 4x4 with 50 symbols. Other dictionaries are also supported by setting the appropriate parameter over serial port or in a config file, up to 7x7 with 1000 symbols.

Creating and printing ArUco markers

To create some markers, have a look at the samples here: https://github.com/opencv/opencv_contrib/tree/master/modules/aruco

To make sure that the files you compile are compatible with JeVois which uses OpenCV 3.2.0 release, get that exact release from GitHub as opposed to just the latest version of those files:

wget wget https://github.com/opencv/opencv_contrib/archive/3.2.0.tar.gz
tar zxvf 3.2.0.tar.gz
# The files referenced below are in: opencv_contrib-3.2.0/modules/aruco/samples/

To compile the sample program that can generate some ArUco markers (e.g., to be printed on paper):

g++ -I/usr/share/jevois-opencv-3.2.0/include -L/usr/share/jevois-opencv-3.2.0/lib create_marker.cpp \\
-o create_marker -lopencv_core -lopencv_imgcodecs -lopencv_highgui -lopencv_aruco
#define o
#define L(i, x, y, z)

Then, to make images of the markers in dictionary 0 (4x4_50):

for id in {0..49}; do ./create_marker -d=0 --id=${id} aruco${id}.png; done

You can then print them and later detect them using this Component. Make sure you select the same dictionary in the component as you did when you generated the markers.

Recovering 3D pose of markers

To enable recovery of the 3D pose of a marker, you need to calibrate your camera. Again using the sample code:

g++ -I/usr/share/jevois-opencv-3.2.0/include -L/usr/share/jevois-opencv-3.2.0/lib create_board_charuco.cpp \\
-o create_board_charuco -lopencv_core -lopencv_imgcodecs -lopencv_highgui -lopencv_aruco -lopencv_imgproc -lopencv_videoio
g++ -I/usr/share/jevois-opencv-3.2.0/include -L/usr/share/jevois-opencv-3.2.0/lib calibrate_camera_charuco.cpp \\
-o calibrate_camera_charuco -lopencv_core -lopencv_imgcodecs -lopencv_highgui -lopencv_aruco -lopencv_imgproc -lopencv_videoio

To create a ChArUco board that can be printed, using dictionary 0, and then derive the camera parameters from it (set the --ml and --sl parameters to what you measure on your printed board; below are what we measured after printing the 5x8 charuco board on US Letter paper with auto scaling/rotate to fit paper):

./create_board_charuco -d=0 -h=5 -w=8 --ml=200 --sl=350 charuco.png
./calibrate_camera_charuco -d=0 -h=5 -w=8 --ml=.0172 --sl=.0303 --rs --sc calibration.yaml
int h

Definition at line 130 of file ArUco.H.

Constructor & Destructor Documentation

◆ ~ArUco()

ArUco::~ArUco ( )
virtual

Destructor.

Definition at line 57 of file ArUco.C.

Member Function Documentation

◆ detectMarkers()

void ArUco::detectMarkers ( cv::InputArray  image,
cv::OutputArray  ids,
cv::OutputArrayOfArrays  corners 
)

Detect markers.

Definition at line 114 of file ArUco.C.

References itsDetector.

◆ drawDetections() [1/2]

void ArUco::drawDetections ( jevois::GUIhelper helper,
std::vector< int >  ids,
std::vector< std::vector< cv::Point2f > >  corners,
std::vector< cv::Vec3d > const &  rvecs,
std::vector< cv::Vec3d > const &  tvecs 
)

◆ drawDetections() [2/2]

void ArUco::drawDetections ( jevois::RawImage outimg,
int  txtx,
int  txty,
std::vector< int >  ids,
std::vector< std::vector< cv::Point2f > >  corners,
std::vector< cv::Vec3d > const &  rvecs,
std::vector< cv::Vec3d > const &  tvecs 
)

◆ estimatePoseSingleMarkers()

void ArUco::estimatePoseSingleMarkers ( cv::InputArrayOfArrays  corners,
cv::OutputArray  rvecs,
cv::OutputArray  tvecs 
)

Estimate pose of individual markers.

Definition at line 120 of file ArUco.C.

References jevois::CameraCalibration::camMatrix, jevois::CameraCalibration::distCoeffs, and itsCalib.

◆ getDictionary()

cv::aruco::Dictionary ArUco::getDictionary ( aruco::Dict  d)
static

Static method to allow anyone to get the ArUco dictionary for a given value of our dictionary parameter.

Definition at line 28 of file ArUco.C.

Referenced by postInit(), and CalibrateCamera::process_frame().

◆ postInit()

void ArUco::postInit ( )
overridevirtual

Initialize, create the detector and read the config files.

Load camera calibration:

Reimplemented from jevois::Component.

Definition at line 61 of file ArUco.C.

References getDictionary(), itsCalib, itsDetector, and LERROR.

◆ postUninit()

void ArUco::postUninit ( )
overridevirtual

Un-initialize, nuke allocated resources.

Reimplemented from jevois::Component.

Definition at line 105 of file ArUco.C.

References itsCalib, and itsDetector.

◆ sendSerial()

void ArUco::sendSerial ( jevois::StdModule mod,
std::vector< int >  ids,
std::vector< std::vector< cv::Point2f > >  corners,
unsigned int  w,
unsigned int  h,
std::vector< cv::Vec3d > const &  rvecs,
std::vector< cv::Vec3d > const &  tvecs 
)

Send serial messages about detections.

The module given should be the owner of this component, we will use it to actually send each serial message using some variant of jevois::Module::sendSerial().

Definition at line 127 of file ArUco.C.

References h, jevois::StdModule::sendSerialContour2D(), and jevois::StdModule::sendSerialStd3D().

Friends And Related Symbol Documentation

◆ JEVOIS_DECLARE_PARAMETER() [1/5]

JEVOIS_DECLARE_PARAMETER ( detparams  ,
std::string  ,
"Filename of detector  parameters,
or empty - Note that " "this parameter cannot be changed at runtime(must be set in the module 's params.cfg)."  ,
""  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [2/5]

JEVOIS_DECLARE_PARAMETER ( dictionary  ,
Dict  ,
"Symbol dictionary to use - Note that " "this parameter cannot be changed at runtime (must be set in the module's params.cfg)."  ,
Dict::D4X4_50  ,
Dict_Values  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [3/5]

JEVOIS_DECLARE_PARAMETER ( dopose  ,
bool  ,
"Compute (and show) pose  vectors,
requires a valid camera calibration"  ,
false  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [4/5]

JEVOIS_DECLARE_PARAMETER ( markerlen  ,
float  ,
"Marker side length   millimeters,
used only for pose estimation"  ,
100.  0F,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [5/5]

JEVOIS_DECLARE_PARAMETER ( showcube  ,
bool  ,
"Show a 3D cube on top of each detected  marker,
when dopose is also true"  ,
false  ,
aruco::ParamCateg   
)
related

Parameter.

◆ JEVOIS_DEFINE_ENUM_CLASS()

JEVOIS_DEFINE_ENUM_CLASS ( Dict  ,
(Original)(D4X4_50)(D4X4_100)(D4X4_250)(D4X4_1000)(D5X5_50)(D5X5_100)(D5X5_250)(D5X5_1000)(D6X6_50)(D6X6_100)(D6X6_250)(D6X6_1000)(D7X7_50)(D7X7_100)(D7X7_250)(D7X7_1000)(ATAG_16h5)(ATAG_25h9)(ATAG_36h10)(ATAG_36h11)   
)
related

Enum for parameter.

Member Data Documentation

◆ itsCalib

jevois::CameraCalibration ArUco::itsCalib
protected

◆ itsDetector

cv::Ptr<cv::aruco::ArucoDetector> ArUco::itsDetector
protected

Definition at line 177 of file ArUco.H.

Referenced by detectMarkers(), postInit(), and postUninit().


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