|
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) |
|
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="") |
|
virtual | ~ParameterRegistry () |
|
|
(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:
- print a calibration board and affix is to a good planar surface (e.g., an acrylic board, aluminum board, etc). Or buy a board, for example from https://calib.io or similar.
- decide which sensor, resolution, and lens you want to calibrate. The sensor should be detected at boot time (check
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.
- set the parameters to match the board type, board width and height in number of tiles, tile size in the unit that you want to later use to estimate distance to detected objects (e.g., in millimeters, inches, etc), and possibly ChArUco marker size and dictionary.
- point the camera towards the board so that the full board is in the camera view. Click 'grab'. Change the viewpoint and repeat at least 5 times. Use various 3D viewpoints.
- click 'calibrate' and the calibration will be computed and saved to microSD for that sensor, resolution, and lens. It will be ready to be loaded by modules that want to use it.
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
- Author
- Laurent Itti
- Display Name:
- Calibrate Camera
- Videomapping:
- YUYV 320 495 30.0 YUYV 320 240 30.0 JeVois DemoArUco
- Videomapping:
- YUYV 640 975 20.0 YUYV 640 480 20.0 JeVois DemoArUco
- Email:
- itti@usc.edu
- Address:
- University of Southern California, HNB-07A, 3641 Watt Way, Los Angeles, CA 90089-2520, USA
- Copyright
- Copyright (C) 2024 by Laurent Itti, iLab and the University of Southern California
- 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 189 of file CalibrateCamera.C.