Package boofcv.abst.geo.calibration
Class CalibrateStereoPlanar
java.lang.Object
boofcv.abst.geo.calibration.CalibrateStereoPlanar
- All Implemented Interfaces:
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 Summary
ConstructorDescriptionCalibrateStereoPlanar
(List<List<Point2D_F64>> layouts) Configures stereo calibration -
Method Summary
Modifier and TypeMethodDescriptionvoid
addPair
(int targetID, List<PointIndex2D_F64> left, List<PointIndex2D_F64> right) Adds a pair of images that observed the same target.computeQualityText
(List<String> namesLeft) Prints statistics based on image residualsstatic String
computeQualityText
(List<String> namesLeft, @Nullable DogArray_B used, List<ImageResults> errors, CalibrationQuality qualityLeft, CalibrationQuality qualityRight) Creates human-readable text with metrics that indicate calibration qualityvoid
configure
(boolean assumeZeroSkew, int numRadialParam, boolean includeTangential) Specify calibration assumptions.void
initialize
(ImageDimension left, ImageDimension right) Puts the class into its initial state.process()
Compute stereo calibration parametersvoid
setVerbose
(@Nullable PrintStream out, @Nullable Set<String> configuration)
-
Constructor Details
-
CalibrateStereoPlanar
Configures stereo calibration- Parameters:
layouts
- How calibration points are laid out on each of the targets
-
-
Method Details
-
initialize
Puts the class into its initial state.- Parameters:
left
- Shape of images from left cameraright
- Shape of images from left camera
-
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 parametersincludeTangential
- If true it will estimate tangential distortion parameters.
-
addPair
Adds a pair of images that observed the same target.- Parameters:
targetID
- The calibration target being observedleft
- Image of left target.right
- Image of right target.
-
process
Compute stereo calibration parameters- Returns:
- Stereo calibration parameters
-
computeQualityText
Prints statistics based on image residuals -
computeQualityText
public static String computeQualityText(List<String> namesLeft, @Nullable @Nullable DogArray_B used, List<ImageResults> errors, CalibrationQuality qualityLeft, CalibrationQuality qualityRight) Creates human-readable text with metrics that indicate calibration quality -
computeErrors
-
setVerbose
public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration) - Specified by:
setVerbose
in interfaceVerbosePrint
-