JeVoisBase
1.23
JeVois Smart Embedded Machine Vision Toolkit Base Modules
|
|
Helper module to calibrate a given sensor+lens combo, which allows ArUco and other modules to do 3D pose estimation. More...
Public Member Functions | |
virtual | ~CalibrateCamera () |
Virtual destructor for safe inheritance. | |
void | process_frame (cv::Mat const &view) |
Process one captured image. | |
void | do_calibration () |
double | computeReprojectionErrors (std::vector< std::vector< cv::Point3f > > const &objectPoints, std::vector< cv::Mat > const &rvecs, std::vector< cv::Mat > const &tvecs, std::vector< float > &perViewErrors) |
void | calcBoardCornerPositions (cv::Size boardsiz, float squaresiz, std::vector< cv::Point3f > &corners) |
bool | runCalibration (std::vector< cv::Mat > &rvecs, std::vector< cv::Mat > &tvecs, std::vector< float > &reprojErrs, double &totalAvgErr, std::vector< cv::Point3f > &newObjPoints) |
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. | |
![]() | |
Module (std::string const &instance) | |
virtual | ~Module () |
virtual void | process (InputFrame &&inframe) |
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) |
![]() | |
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) |
void | hideParam (std::string const ¶mdescriptor, bool doit) |
void | hideAllParams (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) |
void | hideParam (std::string const ¶mdescriptor, bool doit) |
void | hideAllParams (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="") |
![]() | |
virtual | ~ParameterRegistry () |
Protected Member Functions | |
void | restart () |
virtual void | onParamChange (pattern const &par, Pattern const &val) |
Restart when some critical params are changed: | |
virtual void | onParamChange (dictionary const &par, aruco::Dict const &val) |
virtual void | onParamChange (boardSize const &par, cv::Size const &val) |
![]() | |
virtual void | preInit () |
virtual void | postInit () |
virtual void | preUninit () |
virtual void | postUninit () |
virtual void | preInit () |
virtual void | postInit () |
virtual void | preUninit () |
virtual void | postUninit () |
![]() | |
void | addParameter (ParameterBase *const param) |
void | removeParameter (ParameterBase *const param) |
void | callbackInitCall () |
Related Symbols | |
(Note that these are not member symbols.) | |
JEVOIS_DEFINE_ENUM_CLASS (Pattern,(ChessBoard)(ChArUcoBoard)(CirclesGrid)(AsymmetricCirclesGrid)) | |
Enum for parameter. | |
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (pattern, Pattern, "Type of calibration board pattern to use", Pattern::ChessBoard, Pattern_Values, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (dictionary, aruco::Dict, "ArUco dictionary to use", aruco::Dict::D4X4_50, aruco::Dict_Values, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (squareSize, float, "Size of each tile (check) in user-chosen units (e.g., mm, inch, etc). The " "unit used here is the one that will be used once calibrated to report 3D coordinates " "of objects relative to the camera", 23.0f, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (markerSize, float, "ChArUco marker size in user-chosen units (e.g., mm, inch, " "etc). The unit used here is the one that will be used once calibrated to report 3D " "coordinates of objects relative to the camera", 27.0f, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER_WITH_CALLBACK (boardSize, cv::Size, "Board size [width height] in number of horizontal and " "vertical tiles/disks. (Note: for asymmetric circle grid, count the number of " "disks on each row, then the number of rows). The product width * height " "should be the total number of tiles/disks on the grid.)", { 11, 7 }, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (aspectRatio, float, "Fixed aspect ratio value to use when non-zero, or auto when 0.0", 0.0F, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (zeroTangentDist, bool, "Assume zero tangential distortion coefficients P1, P2 and do " "not try to optimize them, i.e., assume board is exactly planar", true, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixPrincipalPoint, bool, "Fix principal point at center, otherwise find its location", true, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fishEye, bool, "Use fisheye model. Should be true if using a wide-angle lens that " "produces significant barrel distortion, otherwise false", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (winSize, unsigned char, "Half of search window size for sub-pixel corner refinement", 11, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK1, bool, "Fix (do not try to optimize) K1 radial distortion parameter", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK2, bool, "Fix (do not try to optimize) K2 radial distortion parameter", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK3, bool, "Fix (do not try to optimize) K3 radial distortion parameter", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK4, bool, "Fix (do not try to optimize) K4 radial distortion parameter", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK5, bool, "Fix (do not try to optimize) K5 radial distortion parameter (not used " "by fisheye lenses)", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (fixK6, bool, "Fix (do not try to optimize) K6 radial distortion parameter (not used " "by fisheye lenses)", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (showUndistorted, bool, "Once calibrated, show undistorted image instead of original capture", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (grab, bool, "Grab one image, try to detect the calibration pattern, and add to list of " "detected patterns so far. Click this for at least 5 images showing your calibration board " "under various viewpoints. When enough boards have been successfully captured, click " "'calibrate'", false, ParamCateg) | |
Parameter. | |
JEVOIS_DECLARE_PARAMETER (calibrate, bool, "Calibrate using all the grabbed boards so far. You first need to grab " "enough good views of your calibration board before you can calibrate.", false, ParamCateg) | |
Parameter. | |
Helper module to calibrate a given sensor+lens combo, which allows ArUco and other modules to do 3D pose estimation.
Just follow the on-screen prompts to calibrate your camera. The calibration results will be saved into /jevois[pro]/share/camera/ on microSD and will be automatically loaded when using a machine vision module that uses camera calibration, for example DemoArUco or FirstVision.
The basic workflow is:
engine::camerasens
system parameter). The lens can be set manually through the engine::cameralens
parameter. The default lens is called "standard". For the resolution, edit videomappings.cfg and add a mode for the CalibrateCamera module that will use the same resolution as the one you want to use later for machine vision. Several commented-out examples are already in videomappings.cfg, so likely you can just uncomment one of them. Then run the corresponding version of the CalibrateCamera module.The default settings are for a 11x7 Chess Board that was created using the online generator at https://calib.io and which you can get from http://jevois.org/data/calib.io_checker_260x200_7x11_23.pdf - When you print the board, make sure you print at 100% scale. You should confirm that the checks in the printout are 23mm x 23mm.
An alternate chess board with fewer checks may be desirable at low resolutions, such as the 7x5 chess board at http://jevois.org/data/calib.io_checker_260x200_5x7_36.pdf - if you use it, set board size to '7 5', and square size to '36' to match it.
If you are using a wide-angle fish-eye lens with a lot of distortion, turn on the fishEye
parameter.
You can also use a ChArUco board, though we have actually obtained worse reprojection errors with these boards. You can print the board at http://jevois.org/data/calib.io_charuco_260x200_5x7_36_27_DICT_4X4.pdf at 100% scale, and you should confirm that the checks in the printout are 36mm x 36mm, and the ArUco patterns within the white checks are 27mm x 27mm. If you use it, you need to set the board type, size, marker size, and square size parameters to match it. An alternate board with more ChArUcos is at http://jevois.org/data/calib.io_charuco_260x200_7x11_23_17_DICT_4X4.pdf
Definition at line 189 of file CalibrateCamera.C.
|
inlinevirtual |
Virtual destructor for safe inheritance.
Definition at line 204 of file CalibrateCamera.C.
|
inline |
Definition at line 433 of file CalibrateCamera.C.
Referenced by runCalibration().
|
inline |
Definition at line 405 of file CalibrateCamera.C.
Referenced by runCalibration().
|
inline |
Definition at line 353 of file CalibrateCamera.C.
References jevois::CameraCalibration::avgReprojErr, jevois::CameraCalibration::camMatrix, jevois::CameraCalibration::distCoeffs, jevois::CameraCalibration::fisheye, jevois::CameraCalibration::h, jevois::CameraCalibration::lens, runCalibration(), jevois::CameraCalibration::sensor, and jevois::CameraCalibration::w.
Referenced by process_frame().
|
inlineprotectedvirtual |
Definition at line 775 of file CalibrateCamera.C.
References restart().
|
inlineprotectedvirtual |
Definition at line 774 of file CalibrateCamera.C.
References restart().
|
inlineprotectedvirtual |
Restart when some critical params are changed:
Definition at line 773 of file CalibrateCamera.C.
References restart().
|
inlineoverridevirtual |
Processing function with zero-copy and GUI on JeVois-Pro.
Reimplemented from jevois::Module.
Definition at line 602 of file CalibrateCamera.C.
References jevois::GUIhelper::drawImage(), jevois::GUIhelper::drawInputFrame(), jevois::GUIhelper::endFrame(), jevois::GUIhelper::iinfo(), jevois::GUIhelper::itext(), process_frame(), restart(), jevois::Timer::start(), jevois::GUIhelper::startFrame(), and jevois::Timer::stop().
|
inlineoverridevirtual |
Processing function with video output to USB.
Reimplemented from jevois::Module.
Definition at line 515 of file CalibrateCamera.C.
References jevois::async(), jevois::yuyv::Black, jevois::rawimage::convertToCvBGR(), jevois::rawimage::drawFilledRect(), h, jevois::RawImage::height, jevois::rawimage::itext(), jevois::rawimage::paste(), jevois::rawimage::pasteBGRtoYUYV(), process_frame(), jevois::RawImage::require(), jevois::Timer::start(), jevois::Timer::stop(), jevois::yuyv::White, jevois::RawImage::width, and jevois::rawimage::writeText().
|
inline |
Process one captured image.
Definition at line 210 of file CalibrateCamera.C.
References do_calibration(), ArUco::getDictionary(), LINFO, and restart().
|
inlineprotected |
Definition at line 763 of file CalibrateCamera.C.
Referenced by onParamChange(), onParamChange(), onParamChange(), process(), and process_frame().
|
inline |
Definition at line 461 of file CalibrateCamera.C.
References calcBoardCornerPositions(), computeReprojectionErrors(), and LINFO.
Referenced by do_calibration().
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Parameter.
|
related |
Enum for parameter.