JeVoisBase  1.20
JeVois Smart Embedded Machine Vision Toolkit Base Modules
Share this page:
FirstVision Class Reference

Simple color-based detection of a U-shaped object for FIRST Robotics. More...

Inheritance diagram for FirstVision:
Collaboration diagram for FirstVision:

Classes

struct  detection
 Helper struct for a detected object. More...
 
struct  hsvcue
 Helper struct for an HSV range triplet, where each range is specified as a mean and sigma: More...
 
class  SinglePoseEstimationParallel
 ParallelLoopBody class for the parallelization of the single markers pose estimation. More...
 

Public Member Functions

 FirstVision (std::string const &instance)
 Constructor. More...
 
virtual ~FirstVision ()
 Virtual destructor for safe inheritance. More...
 
void estimatePose (std::vector< std::vector< cv::Point2f > > &corners, cv::OutputArray _rvecs, cv::OutputArray _tvecs)
 Estimate 6D pose of detected objects, if dopose parameter is true, otherwise just 2D corners. More...
 
void loadCameraCalibration (unsigned int w, unsigned int h)
 Load camera calibration parameters. More...
 
void detect (cv::Mat const &imghsv, size_t tnum, int dispx=3, int dispy=242, jevois::RawImage *outimg=nullptr)
 HSV object detector, we run several of those in parallel with different hsvcue settings. More...
 
void updateHSV (size_t nthreads)
 Initialize (e.g., if user changes cue params) or update our HSV detection ranges. More...
 
void cleanupDetections ()
 Clean up the detections by eliminating duplicates: More...
 
void learnHSV (size_t nthreads, cv::Mat const &imgbgr, jevois::RawImage *outimg=nullptr)
 Learn and update our HSV ranges. More...
 
void sendAllSerial (int w, int h, std::vector< std::vector< cv::Point2f > > const &corners, std::vector< cv::Vec3d > const &rvecs, std::vector< cv::Vec3d > const &tvecs)
 Send serial messages about each detection: More...
 
void updateStructuringElements ()
 Update the morphology structuring elements if needed. More...
 
virtual void process (jevois::InputFrame &&inframe) override
 Processing function, no USB video output. More...
 
virtual void process (jevois::InputFrame &&inframe, jevois::OutputFrame &&outframe) override
 Processing function, with USB video output. More...
 
void drawDetections (jevois::RawImage &outimg, std::vector< std::vector< cv::Point2f > > corners, std::vector< cv::Vec3d > const &rvecs, std::vector< cv::Vec3d > const &tvecs)
 
- 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)
 
 JEVOIS_DEFINE_ENUM_CLASS (SerStyle,(Terse)(Normal)(Detail)(Fine)) JEVOIS_DECLARE_PARAMETER(serstyle
 
 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
 
 JEVOIS_DEFINE_ENUM_CLASS (SerMark,(None)(Start)(Stop)(Both)) JEVOIS_DECLARE_PARAMETER(sermark
 
- 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
 
Engineengine () const
 
bool initialized () const
 
const std::string & className () const
 
const std::string & 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)
 
void unFreezeParam (std::string const &paramdescriptor)
 
void freezeAllParams ()
 
void unFreezeAllParams ()
 
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)
 
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
 
Engineengine () const
 
bool initialized () const
 
const std::string & className () const
 
const std::string & 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)
 
void unFreezeParam (std::string const &paramdescriptor)
 
void freezeAllParams ()
 
void unFreezeAllParams ()
 
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)
 
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 Member Functions

void onParamChange (hcue const &, unsigned char const &) override
 
void onParamChange (scue const &, unsigned char const &) override
 
void onParamChange (vcue const &, unsigned char const &) override
 
- 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 ()
 

Protected Attributes

cv::Mat itsCamMatrix
 Our camera matrix. More...
 
cv::Mat itsDistCoeffs
 Our camera distortion coefficients. More...
 
bool itsCueChanged = true
 True when users change ranges. More...
 
std::vector< hsvcueitsHSV
 
std::vector< detectionitsDetections
 Our detections, combined across all threads. More...
 
std::mutex itsDetMtx
 
std::shared_ptr< Kalman1DitsKalH
 Kalman filters to learn and adapt HSV windows over time. More...
 
std::shared_ptr< Kalman1DitsKalS
 
std::shared_ptr< Kalman1DitsKalV
 
cv::Mat itsErodeElement
 Erosion and dilation kernels shared across all detect threads. More...
 
cv::Mat itsDilateElement
 

Related Functions

(Note that these are not member functions.)

 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (hcue, unsigned char, "Initial cue for target hue (0=red/do not use because of " "wraparound, 30=yellow, 45=light green, 60=green, 75=green cyan, 90=cyan, " "105=light blue, 120=blue, 135=purple, 150=pink)", 45, jevois::Range< unsigned char >(0, 179), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (scue, unsigned char, "Initial cue for target saturation lower bound", 50, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (vcue, unsigned char, "Initial cue for target value (brightness) lower bound", 200, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (maxnumobj, size_t, "Max number of objects to declare a clean image. If more blobs are " "detected in a frame, we skip that frame before we even try to analyze shapes of the blobs", 100, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (hullarea, jevois::Range< unsigned int >, "Range of object area (in pixels) to track. Use this " "if you want to skip shape analysis of very large or very small blobs", jevois::Range< unsigned int >(20 *20, 300 *300), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (hullfill, int, "Max fill ratio of the convex hull (percent). Lower values mean your shape " "occupies a smaller fraction of its convex hull. This parameter sets an upper bound, " "fuller shapes will be rejected.", 50, jevois::Range< int >(1, 100), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (erodesize, size_t, "Erosion structuring element size (pixels), or 0 for no erosion", 2, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (dilatesize, size_t, "Dilation structuring element size (pixels), or 0 for no dilation", 4, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (epsilon, double, "Shape smoothing factor (higher for smoother). Shape smoothing is applied " "to remove small contour defects before the shape is analyzed.", 0.015, jevois::Range< double >(0.001, 0.999), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (debug, bool, "Show contours of all object candidates if true", false, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (threads, size_t, "Number of parallel vision processing threads. Thread 0 uses the HSV values " "provided by user parameters thread 1 broadens that fixed range a bit threads 2-3 use a " "narrow and broader learned HSV window over time", 4, jevois::Range< size_t >(2, 4), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (showthread, size_t, "Thread number that is used to display HSV-thresholded image", 0, jevois::Range< size_t >(0, 3), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (ethresh, double, "Shape error threshold (lower is stricter for exact shape)", 900.0, jevois::Range< double >(0.01, 1000.0), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (dopose, bool, "Compute (and show) 6D object pose, requires a valid camera calibration. " "When dopose is true, 3D serial messages are sent out, otherwise 2D serial messages.", true, ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (camparams, std::string, "File stem of camera parameters, or empty. Camera resolution " "will be appended, as well as a .yaml extension. For example, specifying 'calibration' " "here and running the camera sensor at 320x240 will attempt to load " "calibration320x240.yaml from within directory " JEVOIS_SHARE_PATH "/camera/", "calibration", ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (iou, double, "Intersection-over-union ratio over which duplicates are eliminated", 0.3, jevois::Range< double >(0.01, 0.99), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (objsize, cv::Size_< float >, "Object size (in meters)", cv::Size_< float >(0.28F, 0.175F), ParamCateg)
 Parameter. More...
 
 JEVOIS_DECLARE_PARAMETER (margin, size_t, "Margin from from frame borders (pixels). If any corner of a detected shape " "gets closer than the margin to the frame borders, the shape will be rejected. This is to " "avoid possibly bogus 6D pose estimation when the shape starts getting truncated as it " "partially exits the camera's field of view.", 5, ParamCateg)
 Parameter. More...
 

Detailed Description

Simple color-based detection of a U-shaped object for FIRST Robotics.

This module isolates pixels within a given HSV range (hue, saturation, and value of color pixels), does some cleanups, and extracts object contours. It is looking for a rectangular U shape of a specific size (set by parameter objsize). See screenshots for an example of shape. It sends information about detected objects over serial.

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.

This code was loosely inspired by the JeVois ObjectTracker module. Also see FirstPython for a simplified version of this module, written in Python.

This module is provided for inspiration. It has no pretension of actually solving the FIRST Robotics vision problem in a complete and reliable way. It is released in the hope that FRC teams will try it out and get inspired to develop something much better for their own robot.

General pipeline

The basic idea of this module is the classic FIRST robotics vision pipeline: first, select a range of pixels in HSV color pixel space likely to include the object. Then, detect contours of all blobs in range. Then apply some tests on the shape of the detected blobs, their size, fill ratio (ratio of object area compared to its convex hull's area), etc. Finally, estimate the location and pose of the object in the world.

In this module, we run up to 4 pipelines in parallel, using different settings for the range of HSV pixels considered:

  • Pipeline 0 uses the HSV values provided by user parameters;
  • Pipeline 1 broadens that fixed range a bit;
  • Pipelines 2-3 use a narrow and broader learned HSV window over time.

Detections from all 4 pipelines are considered for overlap and quality (raggedness of their outlines), and only the cleanest of several overlapping detections is preserved. From those cleanest detections, pipelines 2-3 learn and adapt the HSV range for future video frames.

Using this module

Check out this tutorial.

Detection and quality control steps

The following messages appear for each of the 4 pipelines, at the bottom of the demo video, to help users figure out why their object may not be detected:

  • T0 to T3: thread (pipeline) number
  • H=..., S=..., V=...: HSV range considered by that thread
  • N=...: number of raw blobs detected in that range
  • Because N blobs are considered in each thread from this point on, information about only the one that progressed the farthest through a series of tests is shown. One letter is added each time a test is passed:
    • H: the convex hull of the blob is quadrilateral (4 vertices)
    • A: hull area is within range specified by parameter hullarea
    • F: object to hull fill ratio is below the limit set by parameter hullfill (i.e., object is not a solid, filled quadrilateral shape)
    • S: the object has 8 vertices after shape smoothing to eliminate small shape defects (a U shape is indeed expected to have 8 vertices).
    • E: The shape discrepency between the original shape and the smoothed shape is acceptable per parameter ethresh, i.e., the original contour did not have a lot of defects.
    • M: the shape is not too close to the borders of the image, per parameter margin, i.e., it is unlikely to be truncated as the object partially exits the camera's field of view.
    • V: Vectors describing the shape as it related to its convex hull are non-zero, i.e., the centroid of the shape is not exactly coincident with the centroid of its convex hull, as we would expect for a U shape.
    • U: the shape is roughly upright; upside-down U shapes are rejected as likely spurious.
    • OK: this thread detected at least one shape that passed all the tests.

The black and white picture at right shows the pixels in HSV range for the thread determined by parameter showthread (with value 0 by default).

Serial Messages

This module can send standardized serial messages as described in Standardized serial messages formatting. One message is issued on every video frame for each detected and good object. The id field in the messages simply is FIRST for all messages.

When dopose is turned on, 3D messages will be sent, otherwise 2D messages.

2D messages when dopose is off:

  • Serial message type: 2D
  • id: always FIRST
  • x, y, or vertices: standardized 2D coordinates of object center or corners
  • w, h: standardized marker size
  • extra: none (empty string)

3D messages when dopose is on:

  • Serial message type: 3D
  • id: always FIRST
  • x, y, z, or vertices: 3D coordinates in millimeters of object center, or corners
  • w, h, d: object size in millimeters, a depth of 1mm is always used
  • extra: none (empty string)

NOTE: 3D pose estimation from low-resolution 176x144 images at 120fps can be quite noisy. Make sure you tune your HSV ranges very well if you want to operate at 120fps (see below). To operate more reliably at very low resolutions, one may want to improve this module by adding subpixel shape refinement and tracking across frames.

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.

Trying it out

The default parameter settings (which are set in script.cfg explained below) attempt to detect yellow-green objects. Present an object to the JeVois camera and see whether it is detected. When detected and good enough according to a number of quality control tests, the outline of the object is drawn.

For further use of this module, you may want to check out the following tutorials:

Tuning

You need to provide the exact width and height of your physical shape to parameter objsize for this module to work. It will look for a shape of that physical size (though at any distance and orientation from the camera). Be sure you edit script.cfg and set the parameter objsize in there to the true measured physical size of your shape.

You should adjust parameters hcue, scue, and vcue to isolate the range of Hue, Saturation, and Value (respectively) that correspond to the objects you want to detect. Note that there is a script.cfg file in this module's directory that provides a range tuned to a light yellow-green object, as shown in the demo screenshot.

Tuning the parameters is best done interactively by connecting to your JeVois camera while it is looking at some object of the desired color. Once you have achieved a tuning, you may want to set the hcue, scue, and vcue parameters in your script.cfg file for this module on the microSD card (see below).

Typically, you would start by narrowing down on the hue, then the value, and finally the saturation. Make sure you also move your camera around and show it typical background clutter so check for false positives (detections of things which you are not interested, which can happen if your ranges are too wide).

Config file

JeVois allows you to store parameter settings and commands in a file named script.cfg stored in the directory of a module. The file script.cfg may contain any sequence of commands as you would type them interactively in the JeVois command-line interface. For the FirstVision module, a default script is provided that sets the camera to manual color, gain, and exposure mode (for more reliable color values), and other example parameter values.

The script.cfg file for FirstVision is stored on your microSD at JEVOIS:/modules/JeVois/FirstVision/script.cfg

Author
Laurent Itti
Videomapping:
YUYV 176 194 120.0 YUYV 176 144 120.0 JeVois FirstVision
Videomapping:
YUYV 352 194 120.0 YUYV 176 144 120.0 JeVois FirstVision
Videomapping:
YUYV 320 290 60.0 YUYV 320 240 60.0 JeVois FirstVision
Videomapping:
YUYV 640 290 60.0 YUYV 320 240 60.0 JeVois FirstVision
Videomapping:
NONE 0 0 0.0 YUYV 320 240 60.0 JeVois FirstVision
Videomapping:
NONE 0 0 0.0 YUYV 176 144 120.0 JeVois FirstVision
Email:
itti@usc.edu
Address:
University of Southern California, HNB-07A, 3641 Watt Way, Los Angeles, CA 90089-2520, USA
Main URL:
http://jevois.org
Support URL:
http://jevois.org/doc
Other URL:
http://iLab.usc.edu
License:
GPL v3
Distribution:
Unrestricted
Restrictions:
None

Definition at line 292 of file FirstVision.C.

Constructor & Destructor Documentation

◆ FirstVision()

FirstVision::FirstVision ( std::string const &  instance)
inline

Constructor.

Definition at line 403 of file FirstVision.C.

References itsKalH, itsKalS, and itsKalV.

◆ ~FirstVision()

virtual FirstVision::~FirstVision ( )
inlinevirtual

Virtual destructor for safe inheritance.

Definition at line 412 of file FirstVision.C.

Member Function Documentation

◆ cleanupDetections()

void FirstVision::cleanupDetections ( )
inline

Clean up the detections by eliminating duplicates:

Definition at line 653 of file FirstVision.C.

References itsDetections.

Referenced by process().

◆ detect()

void FirstVision::detect ( cv::Mat const &  imghsv,
size_t  tnum,
int  dispx = 3,
int  dispy = 242,
jevois::RawImage outimg = nullptr 
)
inline

◆ drawDetections()

void FirstVision::drawDetections ( jevois::RawImage outimg,
std::vector< std::vector< cv::Point2f > >  corners,
std::vector< cv::Vec3d > const &  rvecs,
std::vector< cv::Vec3d > const &  tvecs 
)
inline

◆ estimatePose()

void FirstVision::estimatePose ( std::vector< std::vector< cv::Point2f > > &  corners,
cv::OutputArray  _rvecs,
cv::OutputArray  _tvecs 
)
inline

Estimate 6D pose of detected objects, if dopose parameter is true, otherwise just 2D corners.

Inspired from the ArUco module of opencv_contrib The corners array is always filled, but rvecs and tvecs only are if dopose is true

Definition at line 418 of file FirstVision.C.

References demo::int, itsCamMatrix, itsDetections, and itsDistCoeffs.

Referenced by PythonObject6D.PythonObject6D::process(), process(), and PythonObject6D.PythonObject6D::processNoUSB().

◆ learnHSV()

void FirstVision::learnHSV ( size_t  nthreads,
cv::Mat const &  imgbgr,
jevois::RawImage outimg = nullptr 
)
inline

Learn and update our HSV ranges.

Definition at line 692 of file FirstVision.C.

References jevois::async(), H, h, itsDetections, itsHSV, itsKalH, itsKalS, itsKalV, and demo::w.

Referenced by process().

◆ loadCameraCalibration()

void FirstVision::loadCameraCalibration ( unsigned int  w,
unsigned int  h 
)
inline

Load camera calibration parameters.

Definition at line 451 of file FirstVision.C.

References freeze(), h, itsCamMatrix, itsDistCoeffs, LERROR, LINFO, to_string(), and demo::w.

Referenced by PythonObject6D.PythonObject6D::process(), process(), and PythonObject6D.PythonObject6D::processNoUSB().

◆ onParamChange() [1/3]

void FirstVision::onParamChange ( hcue const &  ,
unsigned char const &   
)
inlineoverrideprotected

Definition at line 302 of file FirstVision.C.

References itsCueChanged.

◆ onParamChange() [2/3]

void FirstVision::onParamChange ( scue const &  ,
unsigned char const &   
)
inlineoverrideprotected

Definition at line 303 of file FirstVision.C.

References itsCueChanged.

◆ onParamChange() [3/3]

void FirstVision::onParamChange ( vcue const &  ,
unsigned char const &   
)
inlineoverrideprotected

Definition at line 304 of file FirstVision.C.

References itsCueChanged.

◆ process() [1/2]

◆ process() [2/2]

◆ sendAllSerial()

void FirstVision::sendAllSerial ( int  w,
int  h,
std::vector< std::vector< cv::Point2f > > const &  corners,
std::vector< cv::Vec3d > const &  rvecs,
std::vector< cv::Vec3d > const &  tvecs 
)
inline

◆ updateHSV()

void FirstVision::updateHSV ( size_t  nthreads)
inline

Initialize (e.g., if user changes cue params) or update our HSV detection ranges.

Definition at line 608 of file FirstVision.C.

References FirstVision::hsvcue::fix(), itsCueChanged, itsHSV, itsKalH, itsKalS, itsKalV, FirstVision::hsvcue::sih, FirstVision::hsvcue::sis, and FirstVision::hsvcue::siv.

Referenced by process().

◆ updateStructuringElements()

void FirstVision::updateStructuringElements ( )
inline

Update the morphology structuring elements if needed.

Definition at line 784 of file FirstVision.C.

References itsDilateElement, and itsErodeElement.

Referenced by process().

Friends And Related Function Documentation

◆ JEVOIS_DECLARE_PARAMETER() [1/15]

JEVOIS_DECLARE_PARAMETER ( camparams  ,
std::string  ,
"File stem of camera  parameters,
or empty. Camera resolution " "will be  appended,
as well as a .yaml extension. For  example,
specifying 'calibration' " "here and running the camera sensor at 320x240 will attempt to load " "calibration320x240.yaml from within directory " JEVOIS_SHARE_PATH "/camera/"  ,
"calibration"  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [2/15]

JEVOIS_DECLARE_PARAMETER ( debug  ,
bool  ,
"Show contours of all object candidates if true"  ,
false  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [3/15]

JEVOIS_DECLARE_PARAMETER ( dilatesize  ,
size_t  ,
"Dilation structuring element size   pixels,
or 0 for no dilation"  ,
,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [4/15]

JEVOIS_DECLARE_PARAMETER ( dopose  ,
bool  ,
"Compute (and show) 6D object  pose,
requires a valid camera calibration. " "When dopose is  true,
3D serial messages are sent  out,
otherwise 2D serial messages."  ,
true  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [5/15]

JEVOIS_DECLARE_PARAMETER ( epsilon  ,
double  ,
"Shape smoothing factor (higher for smoother). Shape smoothing is applied " "to remove small contour defects before the shape is analyzed."  ,
0.  015,
jevois::Range< double >  0.001, 0.999,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [6/15]

JEVOIS_DECLARE_PARAMETER ( erodesize  ,
size_t  ,
"Erosion structuring element size   pixels,
or 0 for no erosion"  ,
,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [7/15]

JEVOIS_DECLARE_PARAMETER ( ethresh  ,
double  ,
"Shape error threshold (lower is stricter for exact shape)"  ,
900.  0,
jevois::Range< double >  0.01, 1000.0,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [8/15]

JEVOIS_DECLARE_PARAMETER ( hullarea  ,
jevois::Range< unsigned int >  ,
"Range of object area (in pixels) to track. Use this " "if you want to skip shape analysis of very large or very small blobs"  ,
jevois::Range< unsigned int >  20 *20, 300 *300,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [9/15]

JEVOIS_DECLARE_PARAMETER ( hullfill  ,
int  ,
"Max fill ratio of the convex hull (percent). Lower values mean your shape " "occupies a smaller fraction of its convex hull. This parameter sets an upper  bound,
" "fuller shapes will be rejected."  ,
50  ,
jevois::Range< int >  1, 100,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [10/15]

JEVOIS_DECLARE_PARAMETER ( iou  ,
double  ,
"Intersection-over-union ratio over which duplicates are eliminated"  ,
0.  3,
jevois::Range< double >  0.01, 0.99,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [11/15]

JEVOIS_DECLARE_PARAMETER ( margin  ,
size_t  ,
"Margin from from frame borders (pixels). If any corner of a detected shape " "gets closer than the margin to the frame  borders,
the shape will be rejected. This is to " "avoid possibly bogus 6D pose estimation when the shape starts getting truncated as it " "partially exits the camera 's field of view."  ,
,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [12/15]

JEVOIS_DECLARE_PARAMETER ( maxnumobj  ,
size_t  ,
"Max number of objects to declare a clean image. If more blobs are " "detected in a  frame,
we skip that frame before we even try to analyze shapes of the blobs"  ,
100  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [13/15]

JEVOIS_DECLARE_PARAMETER ( objsize  ,
cv::Size_< float >  ,
"Object size (in meters)"  ,
cv::Size_< float >  0.28F, 0.175F,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [14/15]

JEVOIS_DECLARE_PARAMETER ( showthread  ,
size_t  ,
"Thread number that is used to display HSV-thresholded image"  ,
,
jevois::Range< size_t >  0, 3,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER() [15/15]

JEVOIS_DECLARE_PARAMETER ( threads  ,
size_t  ,
"Number of parallel vision processing threads. Thread 0 uses the HSV values " "provided by user parameters thread 1 broadens that fixed range a bit threads 2-3 use a " "narrow and broader learned HSV window over time ,
,
jevois::Range< size_t >  2, 4,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [1/3]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( hcue  ,
unsigned char  ,
"Initial cue for target hue (0=red/do not use because of " "wraparound, 30=yellow, 45=light green, 60=green, 75=green cyan, 90=cyan, " "105=light blue, 120=blue, 135=purple, 150=pink)"  ,
45  ,
jevois::Range< unsigned char >  0, 179,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [2/3]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( scue  ,
unsigned char  ,
"Initial cue for target saturation lower bound"  ,
50  ,
ParamCateg   
)
related

Parameter.

◆ JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK() [3/3]

JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK ( vcue  ,
unsigned char  ,
"Initial cue for target value (brightness) lower bound"  ,
200  ,
ParamCateg   
)
related

Parameter.

Member Data Documentation

◆ itsCamMatrix

cv::Mat FirstVision::itsCamMatrix
protected

Our camera matrix.

Definition at line 298 of file FirstVision.C.

Referenced by drawDetections(), estimatePose(), loadCameraCalibration(), and process().

◆ itsCueChanged

bool FirstVision::itsCueChanged = true
protected

True when users change ranges.

Definition at line 300 of file FirstVision.C.

Referenced by onParamChange(), and updateHSV().

◆ itsDetections

std::vector<detection> FirstVision::itsDetections
protected

Our detections, combined across all threads.

Definition at line 357 of file FirstVision.C.

Referenced by cleanupDetections(), estimatePose(), learnHSV(), and process().

◆ itsDetMtx

std::mutex FirstVision::itsDetMtx
protected

Definition at line 358 of file FirstVision.C.

◆ itsDilateElement

cv::Mat FirstVision::itsDilateElement
protected

Definition at line 364 of file FirstVision.C.

Referenced by detect(), and updateStructuringElements().

◆ itsDistCoeffs

cv::Mat FirstVision::itsDistCoeffs
protected

Our camera distortion coefficients.

Definition at line 299 of file FirstVision.C.

Referenced by drawDetections(), estimatePose(), and loadCameraCalibration().

◆ itsErodeElement

cv::Mat FirstVision::itsErodeElement
protected

Erosion and dilation kernels shared across all detect threads.

Definition at line 364 of file FirstVision.C.

Referenced by detect(), and updateStructuringElements().

◆ itsHSV

std::vector<hsvcue> FirstVision::itsHSV
protected

Definition at line 343 of file FirstVision.C.

Referenced by detect(), learnHSV(), and updateHSV().

◆ itsKalH

std::shared_ptr<Kalman1D> FirstVision::itsKalH
protected

Kalman filters to learn and adapt HSV windows over time.

Definition at line 361 of file FirstVision.C.

Referenced by FirstVision(), learnHSV(), and updateHSV().

◆ itsKalS

std::shared_ptr<Kalman1D> FirstVision::itsKalS
protected

Definition at line 361 of file FirstVision.C.

Referenced by FirstVision(), learnHSV(), and updateHSV().

◆ itsKalV

std::shared_ptr<Kalman1D> FirstVision::itsKalV
protected

Definition at line 361 of file FirstVision.C.

Referenced by FirstVision(), learnHSV(), and updateHSV().


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