Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
industrial_calibration Namespace Reference

Classes

class  ArucoGridBoardTargetFinder
 This class finds 2D target features from images of a specified ArUco gridboard target. The main advantage of this kind of target is that partial views still provide usable correspondences. Target features are returned as a map where the marker ID is the key and the image coordinates of the marker corners are the mapped value. More...
 
struct  ArucoGridTarget
 Structure containing relevant data for a ArUco grid target. More...
 
struct  ArucoGridTargetFinderFactory
 
class  ArucoGridTargetFinderWidget
 
class  AspectRatioPixmapLabel
 The AspectRatioPixmapLabel class https://stackoverflow.com/questions/8211982/qt-resizing-a-qlabel-containing-a-qpixmap-while-keeping-its-aspect-ratio. More...
 
class  BadFileException
 Thrown during errors in loading or parsing data files. More...
 
struct  CalibCameraIntrinsics
 
class  CameraIntrinsicCalibrationWidget
 
class  CameraIntrinsicCost
 Cost function for performing 2D camera intrinsic calibration. More...
 
struct  CameraIntrinsicProblem
 Structure containing the relevant data for a camera intrinsic calibration. More...
 
struct  CameraIntrinsicResult
 Results of the camera intrinsic calibration. More...
 
struct  CameraIntrinsics
 Structure representing camera intrinsic parameters for a pin-hole model camera. More...
 
class  CameraIntrinsicsWidget
 
class  CharucoGridBoardTargetFinder
 This class finds 2D features from images of a specified ChArUco gridboard target. The main advantage of this kind of target is that partial views still provide usable correspondences. More...
 
struct  CharucoGridTarget
 Structure containing relevant data for a ChArUco grid target. More...
 
struct  CharucoGridTargetFinderFactory
 
class  CharucoGridTargetFinderWidget
 
class  CircleDetector
 
struct  CircleDetectorParams
 
class  CircleDistCost
 Cost function for the error between a point and a circle. More...
 
struct  CircleFitProblem
 Problem setup info for the circle fit optimization. More...
 
struct  CircleFitResult
 Results for the circle fit optimization. More...
 
class  ConfigurableWidget
 
class  ConfigurableWidgetDialog
 
struct  Correspondence
 A pair of corresponding features in a N-dimensional sensor "image" and 3D target. More...
 
struct  CorrespondenceSampler
 A simple structure for choosing which correspondence indices to use for generating the homography matrix. More...
 
struct  CovarianceException
 Exception related specifically to covariance-related errors. More...
 
struct  CovarianceResult
 Covariance results for optimization parameters. Contains standard deviations, covariances, and correlation coefficients, as well as the original covariance and correlation matrices. More...
 
struct  DefaultCovarianceOptions
 DefaultCovarianceOptions An instance of ceres::Covariance::Options with values better suited to the optimizations in this library. More...
 
class  DHChain
 Robot representation using DH parameters. More...
 
struct  DHTransform
 Struct representing the DH parameters of a single transformation between adjacent links. This struct follows the classical DH parameter convention: Trans[Zi-1](d) * Rot[Zi-1](theta) * Trans[Xi](r) * Rot[Xi](alpha) See for reference. More...
 
class  DualDHChain2D3DCost
 Cost function for performing kinematic calibration between two DH chains, one that holds a 2D camera and one that holds the target. More...
 
class  DualDHChainCost
 Base class for cost functions that perform kinematic calibration between two DH chains, one that holds the camera and one that holds the target. More...
 
class  DualDHChainMeasurementCost
 Cost function for performing kinematic calibration between two DH chains using a measurement of the pose between the camera and target. More...
 
struct  EigenQuaternionPlus
 Local parameterization of an Eigen quaternion. More...
 
class  ExtrinsicHandEye2D3DCost
 Cost function for a hand-eye calibration using 2D observations of 3D features. More...
 
class  ExtrinsicHandEye3D3DCost
 Cost function for a hand-eye calibration using 3D observations of 3D features. More...
 
struct  ExtrinsicHandEye3dProjectionStats
 3D reprojection error statistics (m) More...
 
struct  ExtrinsicHandEyeAnalysisStats
 Position and orientation difference/standard deviation between the location of the camera as determined by the extrinsic calibration vs the per-observation PnP estimations. More...
 
class  ExtrinsicHandEyeCalibrationWidget
 
class  ExtrinsicHandEyeCost
 Base class for hand-eye calibration cost functions. More...
 
struct  ExtrinsicHandEyeProblem2D3D
 
struct  ExtrinsicHandEyeProblem3D3D
 
struct  ExtrinsicHandEyeResult
 
class  ExtrinsicMultiStaticCameraCost
 Cost function for extrinsic calibration of multiple statically mounted 2D cameras. More...
 
struct  ExtrinsicMultiStaticCameraMovingTargetProblem
 
struct  ExtrinsicMultiStaticCameraMovingTargetResult
 
struct  ExtrinsicMultiStaticCameraMovingTargetWristOnlyProblem
 
struct  ExtrinsicMultiStaticCameraMovingTargetWristOnlyResult
 
struct  ExtrinsicMultiStaticCameraOnlyProblem
 
struct  ExtrinsicMultiStaticCameraOnlyResult
 
class  ExtrinsicMultiStaticCameraWristOnlyCost
 Cost function for extrinsic calibration of multiple statically mounted 2D cameras. More...
 
class  ExtrinsicMultiStaticFixedCameraCost
 Cost function for extrinsic calibration of multiple statically mounted 2D cameras. More...
 
class  ExtrinsicMultiStaticFreeCameraCost
 Cost function for extrinsic calibration of multiple statically mounted 2D cameras. More...
 
struct  GridCorrespondenceSampler
 A correspondence sampler specifically for grid targets. More...
 
class  ICalException
 Exception for general industrial calibration errors. More...
 
struct  IntrinsicCalibrationAccuracyResult
 Structure containing measurements of the intrinsic calibration accuracy. More...
 
struct  KinematicCalibrationProblem2D3D
 
struct  KinematicCalibrationProblemPose6D
 
struct  KinematicCalibrationResult
 
struct  KinematicMeasurement
 A set of data representing a single measurement of the state of a system where a kinematic device holding a "camera" directly observes the position and orientation of a target mounted on a separate kinematic device. More...
 
struct  KinematicObservation
 A set of data representing a single observation of a calibration target. More...
 
class  MaximumLikelihood
 Cost function for a parameter block based on the expected means and standard deviations for the values in the block. The inputs are an array of mean values and an array of standard deviations corresponding to the optimization variables in the parameter block. More...
 
struct  ModifiedCircleGridTarget
 Structure containing the necessary data to represent a modified circle grid target. More...
 
class  ModifiedCircleGridTargetFinder
 This class finds 2D features (circle centers) from images of a known ModifiedCircleGridTarget. All points must be seen or it will fail. Features are returned in the same order as points are defined in the target. More...
 
struct  ModifiedCircleGridTargetFinderFactory
 
class  ModifiedCircleGridTargetFinderWidget
 
class  MultiCameraPnPCost
 Cost function for multi-camera perspective-n-point estimation. More...
 
struct  MultiCameraPnPProblem
 
struct  MultiCameraPnPResult
 
struct  MutableCalibCameraIntrinsics
 
struct  NamedParam
 A double value identified by one or two name strings. More...
 
struct  Observation
 A set of data representing a single observation of a calibration target. This consists of the feature correspondences as well as the transforms to the "mount" frames of the camera and target. For a moving camera or target, the "mount" pose would likely be the transform from the robot base to the robot tool flange. For a stationary camera or target, this "mount" pose would simply be identity. More...
 
struct  OptimizationException
 Exception related specifically to optimization-related errors. More...
 
struct  PnP3DCost
 Cost function for single-camera perspective-n-point estimation using 3D features. More...
 
struct  PnPCost
 Cost function for single camera perspective-n-point estimation. More...
 
struct  PnPNoiseStat
 Noise statistics for a position vector and quaternion orientation. More...
 
struct  PnPProblem
 Structure containing relevant data for a PnP optimization using 2D data. More...
 
struct  PnPProblem3D
 Structure containing relevant data for a PnP optimization using 3D data. More...
 
struct  PnPResult
 PnP optimization results structure. More...
 
struct  Pose6d
 Representation of an isometry homogeneous transform for better integration with Ceres. More...
 
struct  PositionStats
 Holds the mean and standard deviation of a position vector. More...
 
struct  QuaternionStats
 Contains the mean and standard deviation of a quaternion orientation. More...
 
struct  RandomCorrespondenceSampler
 A correspondence sampler that randomly chooses a specifiable number of correspondence indices with a uniform probablility to use in generating a homography transform. More...
 
struct  Target
 Base class for calibration target definitions. More...
 
class  TargetFinder
 Base class for target finders. More...
 
struct  TargetFinderFactoryOpenCV
 Plugin interface for generating OpenCV-based target finders. More...
 
class  TargetFinderWidget
 
class  TransformGuess
 
struct  VirtualCorrespondenceResult
 Structure containing the error measurements between 2 virtual correspondence sets within one real correspondence set. More...
 

Typedefs

template<typename T >
using Isometry3 = Eigen::Transform< T, 3, Eigen::Isometry >
 
template<typename T >
using Quaternion = Eigen::Quaternion< T >
 
template<typename T >
using AngleAxis = Eigen::AngleAxis< T >
 
template<typename T >
using Vector4 = Eigen::Matrix< T, 4, 1 >
 
template<typename T >
using Vector3 = Eigen::Matrix< T, 3, 1 >
 
template<typename T >
using Vector2 = Eigen::Matrix< T, 2, 1 >
 
template<Eigen::Index DIM>
using VectorEigenVector = std::vector< Eigen::Matrix< double, DIM, 1 >, Eigen::aligned_allocator< Eigen::Matrix< double, DIM, 1 > > >
 Typedef for an STL vector of Eigen vector objects. Use a specialized allocator in the case that types divisible by 16 bytes are used, specifically Eigen::Vector2d.
 
template<Eigen::Index DIM>
using TargetFeatures = std::map< unsigned, VectorEigenVector< DIM > >
 Typedef for a container of target features from a calibration target. This definition allows for multiple features to be associated with a single unique identifier (such as the corners of an ArUco tag)
 
using TargetFeatures2D = TargetFeatures< 2 >
 Typedef for target features that exist in 2 dimensions (e.g., pixels from a 2D image)
 
using TargetFeatures3D = TargetFeatures< 3 >
 Typedef for target features that exist in 3 dimensions (e.g., points from a point cloud)
 
using Target2D3D = Target< 2, 3 >
 Target mapping 2-dimensional sensor measurements (e.g., from a 2D camera) to a 3-dimensional world space.
 
using Target3D3D = Target< 3, 3 >
 Target mapping 3-dimensional sensor measurements (e.g., from a 3D sensor) to a 3-dimensional world space.
 
using Correspondence2D3D = Correspondence< 2, 3 >
 Typedef for correspondence between 2D feature in image coordinates and 3D feature in target coordinates.
 
using Correspondence3D3D = Correspondence< 3, 3 >
 Typedef for correspondence between 3D feature in sensor coordinates and 3D feature in target coordinates.
 
using CorrespondenceSet = Correspondence2D3D::Set
 
using Correspondence3DSet = Correspondence3D3D::Set
 
using Observation2D3D = Observation< 2, 3 >
 Typedef for observations of 2D image to 3D target correspondences.
 
using Observation3D3D = Observation< 3, 3 >
 Typedef for observations of 3D sensor to 3D target correspondences.
 
using KinObservation2D3D = KinematicObservation< 2, 3 >
 Typedef for kinematic observations of 2D image to 3D target correspondences.
 
using KinObservation3D3D = KinematicObservation< 3, 3 >
 Typedef for kinematic observations of 3D sensor to 3D target correspondences.
 
template<typename T >
using VectorVector2 = std::vector< Eigen::Matrix< T, 2, 1 >, Eigen::aligned_allocator< Eigen::Matrix< T, 2, 1 > > >
 
template<typename T >
using VectorVector3 = std::vector< Eigen::Matrix< T, 3, 1 >, Eigen::aligned_allocator< Eigen::Matrix< T, 3, 1 > > >
 
using TargetFinderOpenCV = TargetFinder< 2, 3, cv::Mat >
 Typedef for a target finder based on OpenCV that finds 2D targets in an RGB image.
 
using VectorVector2d = std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > >
 

Enumerations

enum class  DHJointType : unsigned { LINEAR , REVOLUTE }
 The joint types for DH representation.
 

Functions

VirtualCorrespondenceResult 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 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:
 
std::ostream & operator<< (std::ostream &stream, const ExtrinsicHandEyeAnalysisStats &stats)
 
ExtrinsicHandEyeAnalysisStats analyzeResults (const ExtrinsicHandEyeProblem2D3D &problem, const ExtrinsicHandEyeResult &opt_result)
 Analyzes the results of the hand eye calibration by measuring the difference between the calibrated camera to target transform and a PnP optimization estimation of the same transform.
 
std::ostream & operator<< (std::ostream &stream, const ExtrinsicHandEye3dProjectionStats &stats)
 
ExtrinsicHandEye3dProjectionStats analyze3dProjectionError (const ExtrinsicHandEyeProblem2D3D &problem, const ExtrinsicHandEyeResult &opt_result)
 
Eigen::VectorXd calculateHomographyError (const Correspondence2D3D::Set &correspondences, const CorrespondenceSampler &correspondence_sampler)
 Computes the error between a set of corresponding planar data points (points on a planar target and their corresponding locations in the image plane) This function creates a homography matrix which transforms data from one plane onto another plane (i.e. from the target plane to the image plane). This matrix is created using only a subset of the correspondences. The matrix is then used to estimate the location of all target points in the image plane. The error between these estimates and the actual values is a good measurement of how accurately a set of 2D camera measurements represent a calbration target with known geometry.
 
PnPNoiseStat qualifyNoise2D (const std::vector< PnPProblem > &params)
 This function qualifies 2D sensor noise by comparing PnP results from images taken at same pose. Sensor noise can be understood by inspecting the returned standard deviations.
 
PnPNoiseStat qualifyNoise3D (const std::vector< PnPProblem3D > &params)
 This function qualifies 3D sensor noise by comparing PnP results from scans taken at the same pose. Sensor noise can be understood by inspecting the returned standard deviations.
 
Eigen::Vector3d computeLinePlaneIntersection (const Eigen::Vector3d &plane_normal, const Eigen::Vector3d &plane_pt, const Eigen::Vector3d &line, const Eigen::Vector3d &line_pt, const double epsilon=1.0e-6)
 Computes the vector from an input point on a line to the point where the line intersects with the input plane See this link for more information.
 
Eigen::MatrixX3d project3D (const Eigen::MatrixX2d &source, const Eigen::Isometry3d &source_to_plane, const Eigen::Matrix3d &k)
 Projects a set of 2D source points (e.g., from an image observation) onto a 3D plane (e.g., a flat calibration target)
 
Eigen::ArrayXd compute3DProjectionError (const Observation2D3D &obs, const CameraIntrinsics &intr, const Eigen::Isometry3d &camera_mount_to_camera, const Eigen::Isometry3d &target_mount_to_target)
 Projects the 2D target features from an observation onto the 3D plane of the calibrated target and computes the difference between the projections and the known target features.
 
Eigen::ArrayXd compute3DProjectionError (const Observation2D3D::Set &obs, const CameraIntrinsics &intr, const Eigen::Isometry3d &camera_mount_to_camera, const Eigen::Isometry3d &target_mount_to_target)
 Projects the 2D target features from a set of observations onto the 3D plane of the calibrated target and computes the difference between the projections and the known target features.
 
std::tuple< double, double > computeStats (const std::vector< double > &values)
 Computes the mean and sample standard deviation statistics of a set of values.
 
QuaternionStats computeQuaternionStats (const std::vector< Eigen::Quaterniond > &quaternions)
 Computes the mean and standard deviation of a set of quaternions.
 
Eigen::Quaterniond computeQuaternionMean (const std::vector< Eigen::Quaterniond > &orientations)
 Computes the mean of a set of quaternions.
 
std::ostream & operator<< (std::ostream &stream, const CameraIntrinsics &intr)
 
template<typename FloatT >
Eigen::Transform< FloatT, 3, Eigen::Isometry > toIsometry (const Eigen::Vector3d &trans, const Eigen::Vector3d &euler_zyx)
 
template<typename T >
getMember (const YAML::Node &n, const std::string &key)
 
void writeTransform (std::stringstream &stream, const Eigen::Isometry3d &transform)
 
std::ostream & operator<< (std::ostream &stream, const CameraIntrinsicResult &result)
 
CameraIntrinsicResult optimize (const CameraIntrinsicProblem &params)
 Performs the camera intrinsic calibration.
 
template<typename T >
void transformPoint (const T angle_axis[3], const T tx[3], const T point[3], T t_point[3])
 
template<typename T >
void poseTransformPoint (const Pose6d &pose, const T point[3], T t_point[3])
 
template<typename T >
void projectPoint (const CameraIntrinsics &intr, const T point[3], T xy_image[2])
 
template<typename T >
Eigen::Matrix< T, 2, 1 > projectPoint (const CameraIntrinsics &intr, const Eigen::Matrix< T, 3, 1 > &point)
 
template<typename T >
VectorVector2< T > projectPoints (const Eigen::Transform< T, 3, Eigen::Isometry > &camera_to_target, const CameraIntrinsics &intr, const VectorVector3< T > &target_points)
 
template<typename T >
void projectPoints2 (const T *const camera_intr, const T *const pt_in_camera, T *pt_in_image)
 
template<typename T >
Eigen::Transform< T, 3, Eigen::Isometry > toIsometry (const T *angle_axis_ptr, const T *translation_ptr)
 
Pose6d poseEigenToCal (const Eigen::Isometry3d &pose)
 
Eigen::Isometry3d poseCalToEigen (const Pose6d &pose)
 
CovarianceResult computeCovarianceResults (const Eigen::MatrixXd &cov_matrix, const std::vector< std::string > &parameter_names)
 Get the covariance results provided covariance matrix and parameter names.
 
Eigen::MatrixXd computeCorrelationsFromCovariance (const Eigen::MatrixXd &covariance_matrix)
 Given a covariance matrix, calculate the matrix of standard deviations and correlation coefficients.
 
CovarianceResult computeCovariance (ceres::Problem &problem, const std::map< const double *, std::vector< int > > &param_masks=std::map< const double *, std::vector< int > >(), const ceres::Covariance::Options &options=DefaultCovarianceOptions())
 Compute all covariance results for a Ceres optimization problem. Labels results with generic names.
 
CovarianceResult computeCovariance (ceres::Problem &problem, const std::vector< const double * > &parameter_blocks, const std::map< const double *, std::vector< int > > &param_masks=std::map< const double *, std::vector< int > >(), const ceres::Covariance::Options &options=DefaultCovarianceOptions())
 Compute covariance results for the specified parameter blocks in a Ceres optimization problem. Labels results with generic names.
 
CovarianceResult computeCovariance (ceres::Problem &problem, const std::map< const double *, std::vector< std::string > > &param_names, const std::map< const double *, std::vector< int > > &param_masks=std::map< const double *, std::vector< int > >(), const ceres::Covariance::Options &options=DefaultCovarianceOptions())
 Compute all covariance results for a Ceres optimization problem and label them with the provided names.
 
CovarianceResult computeCovariance (ceres::Problem &problem, const std::vector< const double * > &parameter_blocks, const std::map< const double *, std::vector< std::string > > &param_names, const std::map< const double *, std::vector< int > > &param_masks=std::map< const double *, std::vector< int > >(), const ceres::Covariance::Options &options=DefaultCovarianceOptions())
 Compute covariance results for specified parameter blocks in a Ceres optimization problem and label them with the provided names.
 
std::vector< int > createDHMask (const Eigen::Array< bool, Eigen::Dynamic, 4 > &mask)
 Create a mask of parameter indices from a matrix of boolean values The indices are calculated in column-wise order because Eigen stores it's values internally in column-wise order by default.
 
KinematicCalibrationResult optimize (const KinematicCalibrationProblem2D3D &problem)
 Performs the kinematic calibration optimization with 2D-3D correspondences.
 
KinematicCalibrationResult optimize (const KinematicCalibrationProblemPose6D &problem, const double orientation_weight=100.0, const ceres::Solver::Options &options=ceres::Solver::Options())
 Performs the kinematic calibration optimization with 6D pose measurements.
 
std::ostream & operator<< (std::ostream &stream, const ExtrinsicHandEyeResult &result)
 
ExtrinsicHandEyeResult optimize (const ExtrinsicHandEyeProblem2D3D &params)
 
ExtrinsicHandEyeResult optimize (const ExtrinsicHandEyeProblem3D3D &params)
 
ExtrinsicMultiStaticCameraMovingTargetResult optimize (const ExtrinsicMultiStaticCameraMovingTargetProblem &params)
 
ExtrinsicMultiStaticCameraOnlyResult optimize (const ExtrinsicMultiStaticCameraOnlyProblem &params)
 
ExtrinsicMultiStaticCameraMovingTargetWristOnlyResult optimize (const ExtrinsicMultiStaticCameraMovingTargetWristOnlyProblem &params)
 
void addSubsetParameterization (ceres::Problem &problem, const std::map< const double *, std::vector< int > > &param_masks)
 Adds subset parameterization for all parameter blocks for a given problem.
 
MultiCameraPnPResult optimize (const MultiCameraPnPProblem &params)
 
std::ostream & operator<< (std::ostream &stream, const PnPResult &result)
 
PnPResult optimize (const PnPProblem &params)
 Performs the PnP optimization.
 
PnPResult optimize (const PnPProblem3D &params)
 Performs the PnP 3D optimization.
 
Eigen::Isometry3d createTransform (const Eigen::Vector3d &t, const Eigen::Vector3d &aa)
 
void printLabels (const std::string &block_name, const std::vector< std::string > &param_labels)
 
void printOptimizationLabels (ceres::Problem &problem, const std::map< const double *, std::string > &names, const std::map< const double *, std::vector< std::string > > &labels, const std::map< const double *, std::vector< int > > &masks)
 
bool isPointVisible (const Pose6d &camera_to_camera_mount, const Pose6d &target_mount_to_target, const ExtrinsicHandEye2D3DCost *cost_fn)
 
void drawReprojections (const VectorVector2d &reprojections, int size, cv::Scalar color, cv::Mat &image)
 Draws reprojected points onto an image.
 
cv::Mat readImageOpenCV (const std::string &path)
 Reads and image from file into an OpenCV matrix.
 
DetectionResult findCircles (const cv::Mat &image, const double threshold, const CircleDetectorParams &params)
 Helper function for finding circles within an image This function thresholds the input image at the input intensity, applies filtering, and attempts to find circles from contours in the image.
 
std::vector< DetectionResult > applyThresholds (const cv::Mat &image, const CircleDetectorParams &params)
 Applies various thresholds to the input image and attempts to find all circles within the images.
 
std::vector< cv::KeyPoint > detectKeyPoints (const std::vector< std::vector< CircleDetector::Center > > &all_centers, const CircleDetectorParams &params)
 Given a list of potential circle centers acquired from differently threshold-ed images, this function matches circle centers that are close in position and radius, and performs a weighted average of their position and radius to create keypoints.
 
template<typename T >
bool isEqual (const T &a, const T &b, const T &tol=std::numeric_limits< T >::epsilon())
 
CircleFitResult optimize (const CircleFitProblem &params)
 Function that solves the circle fit problem.
 

Detailed Description

ChAruco gridboard detector, following the same pattern as ModifiedCircleGridTargetFinder. Author: John Berkebile

Function Documentation

◆ computeCovarianceResults()

CovarianceResult industrial_calibration::computeCovarianceResults ( const Eigen::MatrixXd &  cov_matrix,
const std::vector< std::string > &  parameter_names 
)
Parameters
cov_matrixThe covariance matrix
parameter_namesThe parameter names
Returns
The covariance results

◆ computeCorrelationsFromCovariance()

Eigen::MatrixXd industrial_calibration::computeCorrelationsFromCovariance ( const Eigen::MatrixXd &  covariance_matrix)
Parameters
Covariancematrix
Returns
Matrix of standard deviations (diagonal elements) and correlation coefficents (off-diagonal elements).
Exceptions
CovarianceExceptionif covariance_matrix is not square.

◆ computeCovariance() [1/4]

CovarianceResult industrial_calibration::computeCovariance ( ceres::Problem &  problem,
const std::map< const double *, std::vector< int > > &  param_masks = std::map<const double*, std::vector<int>>(),
const ceres::Covariance::Options &  options = DefaultCovarianceOptions() 
)
Parameters
problemThe Ceres problem (after optimization).
param_masksMap of the parameter block pointer and the indices of the parameters within that block to be excluded from the covariance calculation
optionsceres::Covariance::Options to use when calculating covariance.
Returns
CovarianceResult for the problem.

◆ computeCovariance() [2/4]

CovarianceResult industrial_calibration::computeCovariance ( ceres::Problem &  problem,
const std::vector< const double * > &  parameter_blocks,
const std::map< const double *, std::vector< int > > &  param_masks = std::map<const double*, std::vector<int>>(),
const ceres::Covariance::Options &  options = DefaultCovarianceOptions() 
)
Parameters
problemThe Ceres problem (after optimization).
parameter_blocksSpecific parameter blocks to compute covariance between.
param_masksMap of the parameter block pointer and the indices of the parameters within that block to be excluded from the covariance calculation
optionsceres::Covariance::Options to use when calculating covariance.
Returns
CovarianceResult for the problem.

◆ computeCovariance() [3/4]

CovarianceResult industrial_calibration::computeCovariance ( ceres::Problem &  problem,
const std::map< const double *, std::vector< std::string > > &  param_names,
const std::map< const double *, std::vector< int > > &  param_masks = std::map<const double*, std::vector<int>>(),
const ceres::Covariance::Options &  options = DefaultCovarianceOptions() 
)
Parameters
problemThe Ceres problem (after optimization).
parameter_namesLabels for all optimization parameters in the problem.
param_masksMap of the parameter block pointer and the indices of the parameters within that block to be excluded from the covariance calculation
optionsceres::Covariance::Options to use when calculating covariance.
Returns
CovarianceResult for the problem.

◆ computeCovariance() [4/4]

CovarianceResult industrial_calibration::computeCovariance ( ceres::Problem &  problem,
const std::vector< const double * > &  parameter_blocks,
const std::map< const double *, std::vector< std::string > > &  param_names,
const std::map< const double *, std::vector< int > > &  param_masks = std::map<const double*, std::vector<int>>(),
const ceres::Covariance::Options &  options = DefaultCovarianceOptions() 
)
Parameters
problemThe Ceres problem (after optimization).
parameter_blocksSpecific parameter blocks for which covariance will be calculated.
parameter_namesLabels for optimization parameters in the specified blocks.
param_masksMap of the parameter block pointer and the indices of the parameters within that block to be excluded from the covariance calculation
optionsceres::Covariance::Options to use when calculating covariance.
Returns
CovarianceResult for the problem.
Exceptions
CovarianceExceptionif covariance.Compute fails.
CovarianceExceptionif covariance.GetCovarianceMatrix fails.
CovarianceExceptionif parameter_names.size() != parameter_blocks.size().
CovarianceExceptionif the number of parameter label strings provided for a block is different than the number of parameters in that block.

◆ createDHMask()

std::vector< int > industrial_calibration::createDHMask ( const Eigen::Array< bool, Eigen::Dynamic, 4 > &  mask)
inline
Parameters
mask
Returns

◆ addSubsetParameterization()

void industrial_calibration::addSubsetParameterization ( ceres::Problem &  problem,
const std::map< const double *, std::vector< int > > &  param_masks 
)
Parameters
problem- Ceres optimization problem
param_masks- A map of parameter to an array of masks indicating the index of the parameters that should be held constant.
  • The map must be the same size as the number of parameter blocks in the problem
  • If all parameters are masked it sets that block to constant
Exceptions
OptimizationException

◆ findCircles()

DetectionResult industrial_calibration::findCircles ( const cv::Mat &  image,
const double  threshold,
const CircleDetectorParams params 
)
Parameters
image- grayscale image
threshold- threshold intensity
params- circle detection parameters
Returns

◆ applyThresholds()

std::vector< DetectionResult > industrial_calibration::applyThresholds ( const cv::Mat &  image,
const CircleDetectorParams params 
)
Parameters
image- grayscale image
params- circle detection parameters
Returns

◆ detectKeyPoints()

std::vector< cv::KeyPoint > industrial_calibration::detectKeyPoints ( const std::vector< std::vector< CircleDetector::Center > > &  all_centers,
const CircleDetectorParams params 
)
Parameters
all_centers- a vector of vector of circle centers acquired from images with different threshold values
params- circle detection parameters
Returns

◆ optimize()

CircleFitResult industrial_calibration::optimize ( const CircleFitProblem params)
Parameters
Inputobservations and guesses.
Returns
Output results.