JeVoisBase
1.22
JeVois Smart Embedded Machine Vision Toolkit Base Modules
|
|
Simple wrapper class over the opencv_contrib ArUco augmented reality markers. More...
#include <jevoisbase/Components/ArUco/ArUco.H>
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 ¶mdescriptor, T const &val) |
void | setParamValUnique (std::string const ¶mdescriptor, T const &val) |
std::vector< std::pair< std::string, T > > | getParamVal (std::string const ¶mdescriptor) const |
T | getParamValUnique (std::string const ¶mdescriptor) const |
std::vector< std::string > | setParamString (std::string const ¶mdescriptor, std::string const &val) |
void | setParamStringUnique (std::string const ¶mdescriptor, std::string const &val) |
std::vector< std::pair< std::string, std::string > > | getParamString (std::string const ¶mdescriptor) const |
std::string | getParamStringUnique (std::string const ¶mdescriptor) const |
void | freezeParam (std::string const ¶mdescriptor, 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 ¶mdescriptor, T const &val) |
void | setParamValUnique (std::string const ¶mdescriptor, T const &val) |
std::vector< std::pair< std::string, T > > | getParamVal (std::string const ¶mdescriptor) const |
T | getParamValUnique (std::string const ¶mdescriptor) const |
std::vector< std::string > | setParamString (std::string const ¶mdescriptor, std::string const &val) |
void | setParamStringUnique (std::string const ¶mdescriptor, std::string const &val) |
std::vector< std::pair< std::string, std::string > > | getParamString (std::string const ¶mdescriptor) const |
std::string | getParamStringUnique (std::string const ¶mdescriptor) const |
void | freezeParam (std::string const ¶mdescriptor, 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 () |
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.
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):
Then, to make images of the markers in dictionary 0 (4x4_50):
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.
To enable recovery of the 3D pose of a marker, you need to calibrate your camera. Again using the sample code:
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):
void ArUco::detectMarkers | ( | cv::InputArray | image, |
cv::OutputArray | ids, | ||
cv::OutputArrayOfArrays | corners | ||
) |
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 | ||
) |
Draw any markers previously detected by detectMarkers()
Definition at line 271 of file ArUco.C.
References jevois::CameraCalibration::camMatrix, jevois::CameraCalibration::distCoeffs, jevois::GUIhelper::drawCircle(), jevois::GUIhelper::drawLine(), jevois::GUIhelper::drawPoly(), jevois::GUIhelper::drawText(), jevois::GUIhelper::itext(), and itsCalib.
Referenced by FirstPython.FirstPython::process(), and PythonObject6D.PythonObject6D::process().
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 | ||
) |
Draw any markers previously detected by detectMarkers()
If txtx,txty are positive, also print a text string there
Definition at line 164 of file ArUco.C.
References jevois::CameraCalibration::camMatrix, jevois::CameraCalibration::distCoeffs, jevois::rawimage::drawDisk(), jevois::rawimage::drawLine(), itsCalib, jevois::yuyv::LightGreen, jevois::yuyv::MedGreen, jevois::yuyv::MedGrey, jevois::yuyv::MedPurple, jevois::yuyv::White, and jevois::rawimage::writeText().
Referenced by FirstPython.FirstPython::process(), and PythonObject6D.PythonObject6D::process().
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.
|
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().
|
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.
|
overridevirtual |
Un-initialize, nuke allocated resources.
Reimplemented from jevois::Component.
Definition at line 105 of file ArUco.C.
References itsCalib, and itsDetector.
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().
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Enum for parameter.
|
protected |
Definition at line 178 of file ArUco.H.
Referenced by drawDetections(), drawDetections(), estimatePoseSingleMarkers(), postInit(), and postUninit().
|
protected |
Definition at line 177 of file ArUco.H.
Referenced by detectMarkers(), postInit(), and postUninit().