Class CalibrateStereoPlanar

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

public class CalibrateStereoPlanar
extends Object
implements VerbosePrint

Given a sequence of observations from a stereo camera compute the intrinsic calibration of each camera and the extrinsic calibration between the two cameras. A Planar calibration grid is used, which must be completely visible in all images.

Calibration is performed by first independently determining the intrinsic parameters of each camera as well as their extrinsic parameters relative to the calibration grid. Then the extrinsic parameters between the two cameras is found by creating two point clouds composed of the calibration points in each camera's view. Then the rigid body motion is found which transforms one point cloud into the other.

See comments in CalibrateMonoPlanar about when the y-axis should be inverted.

  • Constructor Details

    • CalibrateStereoPlanar

      public CalibrateStereoPlanar​(List<Point2D_F64> layout)
      Configures stereo calibration
      Parameters:
      layout - How calibration points are laid out on the target
  • Method Details

    • reset

      public void reset()
      Puts the class into its initial state.
    • configure

      public void configure​(boolean assumeZeroSkew, int numRadialParam, boolean includeTangential)
      Specify calibration assumptions.
      Parameters:
      assumeZeroSkew - If true zero skew is assumed.
      numRadialParam - Number of radial parameters
      includeTangential - If true it will estimate tangential distortion parameters.
    • addPair

      public void addPair​(CalibrationObservation left, CalibrationObservation right)
      Adds a pair of images that observed the same target.
      Parameters:
      left - Image of left target.
      right - Image of right target.
    • process

      public StereoParameters process()
      Compute stereo calibration parameters
      Returns:
      Stereo calibration parameters
    • printStatistics

      public void printStatistics()
    • computeErrors

      public List<ImageResults> computeErrors()
    • setVerbose

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