Class CalibrateMonoPlanar

java.lang.Object
boofcv.abst.geo.calibration.CalibrateMonoPlanar
All Implemented Interfaces:
VerbosePrint

public class CalibrateMonoPlanar extends Object implements VerbosePrint

Performs the full processing loop for calibrating a mono camera from a planar grid. A directory is specified that the images are read in from. Calibration points are detected inside the image and feed into the Zhang99 algorithm for parameter estimation.

Internally it supports status updates for a GUI and skips over bad images. Invoke functions in the following order:

  1. configure(boolean, boofcv.alg.geo.calibration.cameras.Zhang99Camera)
  2. initialize(int, int, java.util.List<java.util.List<georegression.struct.point.Point2D_F64>>)
  3. addImage(boofcv.alg.geo.calibration.CalibrationObservation)
  4. process()
  5. getIntrinsic()

Most 3D operations in BoofCV assume that the image coordinate system is right handed and the +Z axis is pointing out of the camera. In standard image coordinate the origin (0,0) is at the top left corner with +x going to the right and +y going down, then if it is right handed +z will be out of the image. However some times this pseudo standard is not followed and the y-axis needs to be inverted by setting isInverted to true.

  • Field Details

  • Constructor Details

    • CalibrateMonoPlanar

      public CalibrateMonoPlanar()
  • Method Details

    • initialize

      public void initialize(int width, int height, List<List<Point2D_F64>> layouts)
      Resets internal data structures. Must call before adding images
      Parameters:
      width - Image width
      height - Image height
    • configure

      public void configure(boolean assumeZeroSkew, Zhang99Camera camera)
      Specifies the calibration model.
    • configurePinhole

      public void configurePinhole(boolean assumeZeroSkew, int numRadialParam, boolean includeTangential)
    • configureUniversalOmni

      public void configureUniversalOmni(boolean assumeZeroSkew, int numRadialParam, boolean includeTangential)
    • configureKannalaBrandt

      public void configureKannalaBrandt(boolean assumeZeroSkew, int numSymmetric, int numAsymmetric)
    • configureUniversalOmni

      public void configureUniversalOmni(boolean assumeZeroSkew, int numRadialParam, boolean includeTangential, double mirrorOffset)
    • isExpectedShape

      public boolean isExpectedShape(int width, int height)
      Convience function which returns true if the provided shape matches the expected image shape
    • addImage

      public void addImage(CalibrationObservation observation)
      Adds the observations from a calibration target detector.

      Note: If you see two targets in one image then that image is treated as two image, one for each observations.

      Parameters:
      observation - Detected calibration points
    • removeLatestImage

      public void removeLatestImage()
      Removes the most recently added image
    • process

      public <T extends CameraModel> T process()
      After calibration points have been found this invokes the Zhang99 algorithm to estimate calibration parameters. Error statistics are also computed.
    • getTargetToView

      public Se3_F64 getTargetToView(int viewIdx)
      Returns estimated transform from calibration target to camera view
    • computeQualityText

      public String computeQualityText(List<String> imageNames)
    • computeQualityText

      public static String computeQualityText(List<ImageResults> errors, List<String> imageNames, CalibrationQuality quality)
      Creates human-readable text with metrics that indicate calibration quality
    • generateReprojectionErrorHistogram

      public static void generateReprojectionErrorHistogram(double[] thresholds, int[] counts, int totalObservations, StringBuilder builder)
    • computeQuality

      public static void computeQuality(CameraModel intrinsic, ScoreCalibrationFill fillScorer, List<List<Point2D_F64>> targetLayouts, List<CalibrationObservation> observations, CalibrationQuality quality)
      Computes quality metrics to quantify how good of a job the person calibrating did
      Parameters:
      intrinsic - Estimated camera model from calibration
      fillScorer - Used to compute image fill score
      targetLayouts - Known location of points in world coordinates
      observations - Observed calibration points
      quality - (Output) Metrics used to evaluate how good the calibration is
    • printErrors

      public static void printErrors(List<ImageResults> results, PrintStream out)
      Prints out error information to standard out
    • getIntrinsic

      public <T extends CameraModel> T getIntrinsic()
    • setVerbose

      public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration)
      Specified by:
      setVerbose in interface VerbosePrint