JeVoisBase
1.22
JeVois Smart Embedded Machine Vision Toolkit Base Modules
|
|
Simple demo of ArUco and AprilTag augmented reality markers detection and decoding. More...
Public Member Functions | |
DemoArUco (std::string const &instance) | |
Constructor. | |
virtual | ~DemoArUco () |
Virtual destructor for safe inheritance. | |
virtual void | process (jevois::InputFrame &&inframe) override |
Processing function, no video output. | |
virtual void | process (jevois::InputFrame &&inframe, jevois::OutputFrame &&outframe) override |
Processing function with video output to USB. | |
virtual void | process (jevois::InputFrame &&inframe, jevois::GUIhelper &helper) override |
Processing function with zero-copy and GUI on JeVois-Pro. | |
Public Member Functions inherited from jevois::StdModule | |
StdModule (std::string const &instance) | |
virtual | ~StdModule () |
void | sendSerialImg1Dx (unsigned int camw, float x, float size=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialStd1Dx (float x, float size=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialImg1Dy (unsigned int camh, float y, float size=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialStd1Dy (float y, float size=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialImg2D (unsigned int camw, unsigned int camh, float x, float y, float w=0.0F, float h=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialStd2D (float x, float y, float w=0.0F, float h=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialContour2D (unsigned int camw, unsigned int camh, std::vector< cv::Point_< T > > points, std::string const &id="", std::string const &extra="") |
void | sendSerialStd3D (float x, float y, float z, float w=0.0F, float h=0.0F, float d=0.0F, float q1=0.0F, float q2=0.0F, float q3=0.0f, float q4=0.0F, std::string const &id="", std::string const &extra="") |
void | sendSerialStd3D (std::vector< cv::Point3f > points, std::string const &id="", std::string const &extra="") |
void | sendSerialObjReco (std::vector< ObjReco > const &res) |
void | sendSerialObjDetImg2D (unsigned int camw, unsigned int camh, float x, float y, float w, float h, std::vector< ObjReco > const &res) |
void | sendSerialObjDetImg2D (unsigned int camw, unsigned int camh, ObjDetect const &det) |
void | sendSerialObjDetImg2D (unsigned int camw, unsigned int camh, ObjDetectOBB const &det) |
JEVOIS_DEFINE_ENUM_CLASS (SerStyle,(Terse)(Normal)(Detail)(Fine)) | |
JEVOIS_DECLARE_PARAMETER (serstyle, SerStyle, "Style for standardized serial messages as defined in " "http://jevois.org/doc/UserSerialStyle.html", SerStyle::Terse, SerStyle_Values, ParamCateg) | |
JEVOIS_DECLARE_PARAMETER (serprec, unsigned int, "Number of decimal points in standardized serial messages as " "defined in http://jevois.org/doc/UserSerialStyle.html", 0U, jevois::Range< unsigned int >(0U, 10U), ParamCateg) | |
JEVOIS_DEFINE_ENUM_CLASS (SerStamp,(None)(Frame)(Time)(FrameTime)(FrameDateTime)) | |
JEVOIS_DECLARE_PARAMETER (serstamp, SerStamp, "Prepend standardized serial messages with a frame number, " "time, frame+time, or frame+date+time. See details in " "http://jevois.org/doc/UserSerialStyle.html", SerStamp::None, SerStamp_Values, ParamCateg) | |
JEVOIS_DEFINE_ENUM_CLASS (SerMark,(None)(Start)(Stop)(Both)) | |
JEVOIS_DECLARE_PARAMETER (sermark, SerMark, "Send serial message to mark the beginning (MARK START) of the " "processing of a video frame from the camera sensor, the end (MARK STOP), or both. " "Useful, among others, if one needs to know when no results were sent over serial " "on a given frame. Combine with parameter serstamp if you need to know the frame number.", SerMark::None, SerMark_Values, ParamCateg) | |
Public Member Functions inherited from jevois::Module | |
Module (std::string const &instance) | |
virtual | ~Module () |
virtual void | sendSerial (std::string const &str) |
virtual void | parseSerial (std::string const &str, std::shared_ptr< UserInterface > s) |
virtual void | supportedCommands (std::ostream &os) |
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 () |
Protected Attributes | |
std::shared_ptr< ArUco > | itsArUco |
Additional Inherited Members | |
Protected Member Functions inherited from jevois::StdModule | |
void | sendSerialMarkStart () |
void | sendSerialMarkStop () |
std::string | getStamp () const |
Protected Member Functions inherited from jevois::Component | |
virtual void | preInit () |
virtual void | postInit () |
virtual void | preUninit () |
virtual void | postUninit () |
virtual void | preInit () |
virtual void | postInit () |
virtual void | preUninit () |
virtual void | postUninit () |
Protected Member Functions inherited from jevois::ParameterRegistry | |
void | addParameter (ParameterBase *const param) |
void | removeParameter (ParameterBase *const param) |
void | callbackInitCall () |
Simple demo of ArUco and AprilTag augmented reality markers detection and decoding.
Detect and decode patterns known as ArUco markers, which are small 2D barcodes often used in augmented reality and robotics.
ArUco and AprilTag markers are small 2D barcodes. Each marker corresponds to a number, encoded into a small grid of black and white pixels. The marker decoding algorithm is capable of locating, decoding, and of estimating the pose (location and orientation in space) of any compatible markers in the camera's field of view.
ArUco and AprilTag markers 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.
The implementation of ArUco used by JeVois is the one of OpenCV-Contrib, documented here: https://docs.opencv.org/4.x/d5/dae/tutorial_aruco_detection.html
ArUco and AprilTag markers can be created with several standard dictionaries. Different dictionaries 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 ArUco 4x4 with 50 symbols. Other dictionaries are also supported by setting the parameter dictionary
over serial port or in a config file, up to 7x7 with 1000 symbols.
We have created the 50 markers available in the default ArUco dictionary (4x4_50) as PNG images that you can download and print, at http://jevois.org/data/ArUco.zip
To make your own, for example, using another dictionary, see the documentation of the ArUco component of JeVoisBase. Some utilities are provided with the component.
This module can send standardized serial messages as described in Standardized serial messages formatting.
When dopose
is turned on, 3D messages will be sent, otherwise 2D messages.
One message is issued for every detected ArUco, on every video frame.
2D messages when dopose
is off:
id
: decoded ArUco marker ID, with a prefix 'U'x
, y
, or vertices: standardized 2D coordinates of marker center or cornersw
, h
: standardized marker sizeextra
: none (empty string)3D messages when dopose
is on:
id
: decoded ArUco marker ID, with a prefix 'U'x
, y
, z
, or vertices: 3D coordinates in millimeters of marker center or cornersw
, h
, d
: marker size in millimeters, a depth of 1mm is always usedextra
: none (empty string)If you will use the quaternion data (Detail message style; see Standardized serial messages formatting), you should probably set the serprec
parameter to something non-zero to get enough accuracy in the quaternion values.
See Standardized serial messages formatting for more on standardized serial messages, and Helper functions to convert coordinates from camera resolution to standardized for more info on standardized coordinates.
dictionary
).setpar serout USB setmapping2 YUYV 320 240 30.0 JeVois DemoArUco streamonand point the camera to some markers; the camera should issue messages about all the markers it identifies.
The OpenCV ArUco module can also compute the 3D location and orientation of each marker in the world when dopose
is true. The requires that the camera be calibrated, see the documentation of the ArUco component in JeVoisBase. A generic calibration that is for a JeVois camera with standard lens is included in files calibration640x480.yaml, calibration352x288.yaml, etc in the jevoisbase share directory (on the MicroSD, this is in JEVOIS:/share/camera/).
When doing pose estimation, you should set the markerlen
parameter to the size (width) in millimeters of your actual physical markers. Knowing that size will allow the pose estimation algorithm to know where in the world your detected markers are.
For more about camera calibration, see this tutorial and http://jevois.org/basedoc/ArUco_8H_source.html
Check out this tutorial on how to build a simple visually-guided toy robot car for under $100 with JeVois, which uses ArUco at its core. A demo video is here:
Definition at line 143 of file DemoArUco.C.
|
inline |
|
inlinevirtual |
Virtual destructor for safe inheritance.
Definition at line 157 of file DemoArUco.C.
|
inlineoverridevirtual |
Processing function, no video output.
Reimplemented from jevois::Module.
Definition at line 163 of file DemoArUco.C.
References jevois::rawimage::convertToCvGray(), h, jevois::RawImage::height, itsArUco, and jevois::RawImage::width.
|
inlineoverridevirtual |
Processing function with zero-copy and GUI on JeVois-Pro.
Reimplemented from jevois::Module.
Definition at line 246 of file DemoArUco.C.
References jevois::rawimage::convertToCvGray(), jevois::GUIhelper::drawInputFrame(), jevois::GUIhelper::endFrame(), h, jevois::RawImage::height, jevois::GUIhelper::iinfo(), jevois::GUIhelper::itext(), itsArUco, jevois::Timer::start(), jevois::GUIhelper::startFrame(), jevois::Timer::stop(), and jevois::RawImage::width.
|
inlineoverridevirtual |
Processing function with video output to USB.
Reimplemented from jevois::Module.
Definition at line 189 of file DemoArUco.C.
References jevois::async(), jevois::yuyv::Black, jevois::rawimage::convertToCvGray(), jevois::rawimage::drawFilledRect(), jevois::RawImage::fmt, h, jevois::RawImage::height, itsArUco, jevois::rawimage::paste(), jevois::RawImage::require(), jevois::Timer::start(), jevois::Timer::stop(), jevois::yuyv::White, jevois::RawImage::width, and jevois::rawimage::writeText().
|
protected |
Definition at line 295 of file DemoArUco.C.
Referenced by DemoArUco(), process(), process(), and process().