Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
Camera Intrinsic Calibration Analysis

Detailed Description

Classes

struct  industrial_calibration::VirtualCorrespondenceResult
 Structure containing the error measurements between 2 virtual correspondence sets within one real correspondence set. More...
 
struct  industrial_calibration::IntrinsicCalibrationAccuracyResult
 Structure containing measurements of the intrinsic calibration accuracy. More...
 

Functions

VirtualCorrespondenceResult industrial_calibration::measureVirtualTargetDiff (const Correspondence2D3D::Set &correspondences, const CameraIntrinsics &intr, const Eigen::Isometry3d &camera_to_target_guess=Eigen::Isometry3d::Identity(), const double pnp_sq_error_threshold=1.0)
 Divides a set of correspondences into two halves and measures the difference in position of one half to the other Method:
 
IntrinsicCalibrationAccuracyResult industrial_calibration::measureIntrinsicCalibrationAccuracy (const Observation2D3D::Set &observations, const CameraIntrinsics &intr, const Eigen::Isometry3d &camera_mount_to_camera, const Eigen::Isometry3d &target_mount_to_target, const Eigen::Isometry3d &camera_base_to_target_base, const double pnp_sq_error_threshold=1.0)
 Calculates the mean and variance of the transform between two virtual correspondence sets (extracted from a single correspondence set) for a set of calibration observations Method:
 

Function Documentation

◆ measureVirtualTargetDiff()

VirtualCorrespondenceResult industrial_calibration::measureVirtualTargetDiff ( const Correspondence2D3D::Set &  correspondences,
const CameraIntrinsics intr,
const Eigen::Isometry3d &  camera_to_target_guess = Eigen::Isometry3d::Identity(),
const double  pnp_sq_error_threshold = 1.0 
)
  1. Split the correspondence set into two virtual correspondence sets
  2. Solve PnP optimization for each virtual correspondence set to get the transform from the camera to the virtual correspondence set
  3. Return the error between the two virtual correspondence sets

Note: the two virtual correspondence sets are composed of different points, but those points are relative to the same origin Therefore, the transformation from one virtual correspondence set to the other should be identity, given perfect camera intrinsic parameters

Parameters
correspondences- set of corresponding observed features and target features
intr- camera intrinsic parameters
camera_to_target_guess- an initial guess about the location of the target relative to the camera (default: identity)
pnp_sq_error_threshold- Max squared error allowed for a PnP optimization. This value should be driven by the accuracy of the sensor providing the observations (default: 1.0 pixel^2)
Returns

◆ measureIntrinsicCalibrationAccuracy()

IntrinsicCalibrationAccuracyResult industrial_calibration::measureIntrinsicCalibrationAccuracy ( const Observation2D3D::Set &  observations,
const CameraIntrinsics intr,
const Eigen::Isometry3d &  camera_mount_to_camera,
const Eigen::Isometry3d &  target_mount_to_target,
const Eigen::Isometry3d &  camera_base_to_target_base,
const double  pnp_sq_error_threshold = 1.0 
)
  1. Check that the correspondences in all observations are the same size
    • Assumptions:
      • Correspondences are ordered in the same way for each observation
      • The correspondences in each observation can be divided in half to get the same two sets of features
  2. Calculate error between two virtual correspondence sets in adjacent observations
  3. Calculate the mean and standard deviation of the positional difference in this error for all observations
    • Theoretically, this difference should be zero for a perfectly intrinsically calibrated camera that perfectly observed the target features
Parameters
observations- a set of calibration observations
intr- camera intrinsic parameters
camera_mount_to_camera- The transformation from the camera mount frame to the camera
target_mount_to_target- The transformation from the target mount frame to the target
camera_base_to_target_base- the transform from the camera base frame to the target base frame (typically identity)
pnp_sq_error_threshold- Max squared error allowed for a PnP optimization. This value should be driven by the accuracy of the sensor providing the observations (default: 1.0 pixel^2)
Returns