JeVoisBase
1.22
JeVois Smart Embedded Machine Vision Toolkit Base Modules
|
|
Combined ArUco marker + multiple color-based object detection. More...
Public Member Functions | |
ArUcoBlob (std::string const &instance) | |
Constructor. | |
void | postInit () override |
Post-init: instantiate the blob detectors. | |
void | preUninit () override |
virtual | ~ArUcoBlob () |
Virtual destructor for safe inheritance. | |
void | detectBlobs () |
Detect blobs in parallel threads. | |
void | sendBlobs (unsigned int w, unsigned int h) |
Gather our blob threads and send/draw the results. | |
void | detectArUco (cv::Mat cvimg, std::vector< int > &ids, std::vector< std::vector< cv::Point2f > > &corners, std::vector< cv::Vec3d > &rvecs, std::vector< cv::Vec3d > &tvecs, unsigned int h, jevois::RawImage *outimg=nullptr) |
Detect ArUcos. | |
virtual void | process (jevois::InputFrame &&inframe) override |
Processing function, no USB video output. | |
virtual void | process (jevois::InputFrame &&inframe, jevois::OutputFrame &&outframe) override |
Processing function, with USB video output. | |
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 | process (InputFrame &&inframe, GUIhelper &helper) |
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 |
std::vector< std::shared_ptr< BlobDetector > > | itsBlobs |
cv::Mat | itsImgHsv |
std::map< std::string, std::vector< std::vector< cv::Point > > > | itsContours |
std::vector< std::future< void > > | itsBlobFuts |
std::mutex | itsBlobMtx |
Related Symbols | |
(Note that these are not member symbols.) | |
JEVOIS_DECLARE_PARAMETER (numtrack, size_t, "Number of parallel blob trackers to run. They will be named blob0, " "blob1, etc for parameters and serial messages", 3, ParamCateg) | |
Parameter. | |
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 | postUninit () |
virtual void | preInit () |
virtual void | postUninit () |
Protected Member Functions inherited from jevois::ParameterRegistry | |
void | addParameter (ParameterBase *const param) |
void | removeParameter (ParameterBase *const param) |
void | callbackInitCall () |
Combined ArUco marker + multiple color-based object detection.
This modules 1) detects ArUco markers (small black-and-white geometric patterns which can be used as tags for some objects), and, in parallel, 2) isolates pixels within multiple given HSV ranges (hue, saturation, and value of color pixels), does some cleanups, and extracts object contours. It sends information about detected ArUco tags and color objects over serial.
This module was developed to allow students to easily develop visually-guided robots that can at the same time detect ArUco markers placed in the environment to signal certain key objects (e.g., charging station, home base) and colored objects of different kinds (e.g., blue people, green trees, and yellow fires).
This module usually works best with the camera sensor set to manual exposure, manual gain, manual color balance, etc so that HSV color values are reliable. See the file script.cfg file in this module's directory for an example of how to set the camera settings each time this module is loaded.
Since this is a combination module, refer to:
The number of parallel blob trackers is determined by parameter numtrack
, which should be set before the module is initialized, i.e., in the module's params.cfg file. It cannot be changed while the module is running.
The module runs at about 50 frames/s with 3 parallel blob detectors plus ArUco, at 320x240 camera sensor resolution. Increasing to 10 parallel blob detectors will still get you about 25 frames/s (but finding robust non-overlapping HSV ranges for all those detectors will become challenging!)
To configure parameters hrange
, srange
, and vrange
for each detector in the module's scrip.cfg, we recommend that you do it one by one for each kind of colored object you want, using the ObjectTracker module (which shares the same color blob detection code, just for one HSV range) and the tutorial on Tuning the color-based object tracker using a python graphical interface, or the sliders in JeVois Inventor. Just make sure that both modules have the same camera settings in their respective script.cfg files.
We recommend the following settings (to apply after you load the module, for example in the module's script.cfg file):
With a scene as shown in this module's screenshots, you would then get outputs like:
... 1557 N2 U42 -328 -9 706 569 1557 N2 U18 338 -241 613 444 1557 N2 blob0 616 91 406 244 1557 N2 blob1 28 584 881 331 1557 N2 blob2 47 -553 469 206 1558 N2 U42 -328 -9 706 569 1558 N2 U18 338 -241 613 444 1558 N2 blob0 547 113 519 275 1558 N2 blob1 28 581 881 338 1558 N2 blob2 47 -553 469 206 1559 N2 U42 -331 -13 700 563 1559 N2 U18 338 -244 613 450 1559 N2 blob0 369 153 200 194 1559 N2 blob0 616 94 381 250 1559 N2 blob1 28 581 881 338 1559 N2 blob2 47 -553 469 206 ...
which basically means that, on frame 1557, ArUco markers U42 and U18 were detected, then blob detector named "blob0" (configured for light blue objects in script.cfg) detected one blob, then "blob1" (configured for yellow) also detected one, and finally "blob2" (configured for green) found one too. That was all for frame 1157, and we then switch to frame 1158 (with essentially the same detections), then frame 1159 (note how blob0 detected 2 different blobs on that frame), and so on. See Standardized serial messages formatting for more info about these messages.
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.
Try these settings in the global initialization script file of JeVois, which is executed when JeVois powers up, in JEVOIS:/config/initscript.cfg:
Make sure you do not have conflicting settings in the module's params.cfg or script.cfg file; as a reminder, the order of execution is: 1) initscript.cfg runs, which loads the module through the setmapping2
command; 2) as part of the loading process and before the module is initialized, settings in params.cfg are applied; 3) the module is then initialized and commands in script.cfg are run; 4) the additional commands following setmapping2
in initscript.cfg are finally run. Next time JeVois starts up, it will automatically load this module and start sending messages to the hardware 4-pin serial port, which you should then connect to an Arduino or other robot controller.
Definition at line 150 of file ArUcoBlob.C.
|
inline |
|
inlinevirtual |
Virtual destructor for safe inheritance.
Definition at line 187 of file ArUcoBlob.C.
|
inline |
|
inline |
Detect blobs in parallel threads.
Definition at line 192 of file ArUcoBlob.C.
References jevois::async(), itsBlobFuts, itsBlobs, and itsContours.
|
inlineoverridevirtual |
Post-init: instantiate the blob detectors.
Reimplemented from jevois::Component.
Definition at line 167 of file ArUcoBlob.C.
References itsBlobs.
|
inlineoverridevirtual |
Reimplemented from jevois::Component.
Definition at line 178 of file ArUcoBlob.C.
References itsBlobs, and jevois::Component::removeSubComponent().
|
inlineoverridevirtual |
Processing function, no USB video output.
Reimplemented from jevois::Module.
Definition at line 240 of file ArUcoBlob.C.
References jevois::rawimage::convertToCvBGR(), jevois::rawimage::convertToCvGray(), detectArUco(), detectBlobs(), h, jevois::RawImage::height, itsArUco, itsImgHsv, sendBlobs(), and jevois::RawImage::width.
|
inlineoverridevirtual |
Processing function, with USB video output.
Reimplemented from jevois::Module.
Definition at line 272 of file ArUcoBlob.C.
References area(), jevois::async(), jevois::rawimage::convertToCvBGR(), jevois::rawimage::convertToCvGray(), jevois::rawimage::cvImage(), detectArUco(), detectBlobs(), jevois::rawimage::drawCircle(), jevois::rawimage::drawFilledRect(), jevois::RawImage::fmt, h, jevois::RawImage::height, itsArUco, itsContours, itsImgHsv, jevois::rawimage::paste(), jevois::RawImage::require(), sendBlobs(), jevois::Timer::start(), jevois::Timer::stop(), jevois::yuyv::White, jevois::RawImage::width, and jevois::rawimage::writeText().
|
inline |
Gather our blob threads and send/draw the results.
Definition at line 209 of file ArUcoBlob.C.
References h, itsBlobFuts, itsContours, LERROR, and jevois::StdModule::sendSerialContour2D().
|
related |
Parameter.
|
protected |
Definition at line 355 of file ArUcoBlob.C.
Referenced by ArUcoBlob(), detectArUco(), process(), and process().
|
protected |
Definition at line 359 of file ArUcoBlob.C.
Referenced by detectBlobs(), and sendBlobs().
|
protected |
Definition at line 360 of file ArUcoBlob.C.
|
protected |
Definition at line 356 of file ArUcoBlob.C.
Referenced by detectBlobs(), postInit(), and preUninit().
|
protected |
Definition at line 358 of file ArUcoBlob.C.
Referenced by detectBlobs(), process(), and sendBlobs().
|
protected |
Definition at line 357 of file ArUcoBlob.C.