Package boofcv.abst.geo.calibration
Class CalibrateMultiPlanar
java.lang.Object
boofcv.abst.geo.calibration.CalibrateMultiPlanar
Multi camera calibration using multiple planar targets. It's assumed that all cameras are rigidly attach and that the calibration targets are static. Camera[0] is always the sensor reference frame. The world reference frame is defined as calibration target[0].
Usage:- Specify camera model via
#getCalibratorMonoand configure* functions - Call
initialize(int, int) - Specify shape of all cameras
setCameraProperties(int, int, int) - Specify target layouts using
setTargetLayout(int, java.util.List<georegression.struct.point.Point2D_F64>) - Call
process()perform calibration. Check results to see if it succeeded - Get found calibration with
#getResults()
- Calibrate each camera independently using monocular approach
- Estimate extrinsic relationship between cameras using common observed targets
- Estimate extrinsic relationship between sensor and world for each frame
- Run bundle adjustment to improve results
Internally it assumes that the targets are stationary and the camera system is moving. It will work just fine if the opposite is true as these are mathematically identical.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classPrior information provided about the camera by the userstatic classCalibration quality statisticsstatic classList of all observation from a camera in a frame.static classWorkspace for information related to a single frame.static classSpecifies which target was observed and what the inferred transform was.. -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected double[]Reprojection error thresholds for histogram in performance summary -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoidaddObservation(SynchronizedCalObs observations) Adds an observation.computeQualityText(boolean showImageStats) Summarizes calibration quality and residual errors in a human-readable text stringvoidinitialize(int numCameras, int numTargets) Must call this function first.booleanprocess()Processes the inputs and estimates the camera system's intrinsic and extrinsic calibration.voidsetCameraProperties(int which, int width, int height) Specifies the shape o images from a specific cameravoidsetTargetLayout(int which, List<Point2D_F64> layout) Specifies location of calibration points for a target.voidsetTargetLayouts(List<List<Point2D_F64>> layouts)
-
Field Details
-
summaryThresholds
protected double[] summaryThresholdsReprojection error thresholds for histogram in performance summary
-
-
Constructor Details
-
CalibrateMultiPlanar
public CalibrateMultiPlanar()
-
-
Method Details
-
initialize
public void initialize(int numCameras, int numTargets) Must call this function first. Specifies the number of cameras and calibration targets -
setCameraProperties
public void setCameraProperties(int which, int width, int height) Specifies the shape o images from a specific camera -
setTargetLayout
Specifies location of calibration points for a target. -
setTargetLayouts
-
addObservation
Adds an observation. Order does not matter. All cameras are assumed to have synchronized shutters and observed the world at the exact same time.- Parameters:
observations- Observed calibration targets in a single fram.
-
process
public boolean process()Processes the inputs and estimates the camera system's intrinsic and extrinsic calibration. If true is returned, then#getResults()will return the found calibration.- Returns:
- true if successful or false if it failed
-
computeQualityText
Summarizes calibration quality and residual errors in a human-readable text string- Parameters:
showImageStats- If true it will print stats for individual images.
-