Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
Core

Detailed Description

Contains definitions for common data types (e.g., features, correspondences, observations, camera intrinsics, etc.) and interface classes.

Typedefs

template<Eigen::Index DIM>
using industrial_calibration::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 industrial_calibration::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 industrial_calibration::TargetFeatures2D = TargetFeatures< 2 >
 Typedef for target features that exist in 2 dimensions (e.g., pixels from a 2D image)
 
using industrial_calibration::TargetFeatures3D = TargetFeatures< 3 >
 Typedef for target features that exist in 3 dimensions (e.g., points from a point cloud)
 
using industrial_calibration::Target2D3D = Target< 2, 3 >
 Target mapping 2-dimensional sensor measurements (e.g., from a 2D camera) to a 3-dimensional world space.
 
using industrial_calibration::Target3D3D = Target< 3, 3 >
 Target mapping 3-dimensional sensor measurements (e.g., from a 3D sensor) to a 3-dimensional world space.
 
using industrial_calibration::Correspondence2D3D = Correspondence< 2, 3 >
 Typedef for correspondence between 2D feature in image coordinates and 3D feature in target coordinates.
 
using industrial_calibration::Correspondence3D3D = Correspondence< 3, 3 >
 Typedef for correspondence between 3D feature in sensor coordinates and 3D feature in target coordinates.
 
using industrial_calibration::Observation2D3D = Observation< 2, 3 >
 Typedef for observations of 2D image to 3D target correspondences.
 
using industrial_calibration::Observation3D3D = Observation< 3, 3 >
 Typedef for observations of 3D sensor to 3D target correspondences.
 
using industrial_calibration::KinObservation2D3D = KinematicObservation< 2, 3 >
 Typedef for kinematic observations of 2D image to 3D target correspondences.
 
using industrial_calibration::KinObservation3D3D = KinematicObservation< 3, 3 >
 Typedef for kinematic observations of 3D sensor to 3D target correspondences.
 

Classes

struct  industrial_calibration::CameraIntrinsics
 Structure representing camera intrinsic parameters for a pin-hole model camera. More...
 
struct  industrial_calibration::CalibCameraIntrinsics< T >
 
struct  industrial_calibration::MutableCalibCameraIntrinsics< T >
 
class  industrial_calibration::DHChain
 Robot representation using DH parameters. More...
 
struct  industrial_calibration::Pose6d
 Representation of an isometry homogeneous transform for better integration with Ceres. More...
 
struct  industrial_calibration::Target< SENSOR_DIM, WORLD_DIM >
 Base class for calibration target definitions. More...
 
class  industrial_calibration::TargetFinder< SENSOR_DIM, WORLD_DIM, SensorDataT >
 Base class for target finders. More...
 
struct  industrial_calibration::Correspondence< SENSOR_DIM, WORLD_DIM >
 A pair of corresponding features in a N-dimensional sensor "image" and 3D target. More...
 
struct  industrial_calibration::Observation< SENSOR_DIM, WORLD_DIM >
 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  industrial_calibration::KinematicObservation< SENSOR_DIM, WORLD_DIM >
 A set of data representing a single observation of a calibration target. More...
 
struct  industrial_calibration::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...
 

Functions

template<typename T >
void industrial_calibration::projectPoint (const CameraIntrinsics &intr, const T point[3], T xy_image[2])
 Projects a 3D point (relative to the camera frame) into image coordinates.
 
template<typename T >
Eigen::Matrix< T, 2, 1 > industrial_calibration::projectPoint (const CameraIntrinsics &intr, const Eigen::Matrix< T, 3, 1 > &point)
 Projects a 3D point (relative to the camera frame) into image coordinates.
 
template<typename T >
VectorVector2< T > industrial_calibration::projectPoints (const Eigen::Transform< T, 3, Eigen::Isometry > &camera_to_target, const CameraIntrinsics &intr, const VectorVector3< T > &target_points)
 Projects a vector of 3D points (relative to the camera frame) into a vector of image coordinates.
 
template<typename T >
void industrial_calibration::projectPoints2 (const T *const camera_intr, const T *const pt_in_camera, T *pt_in_image)
 Projects a 3D point (relative to the camera) into image coordinates, accounting for image distortion.
 
Eigen::Matrix< double, 3, 3, Eigen::RowMajor > industrial_calibration::calculateHomography (const Correspondence2D3D::Set correspondences)
 Computes the homography matrix of a set of correspondences.
 
Eigen::Matrix2Xd industrial_calibration::projectHomography (const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > &H, const Eigen::Matrix2Xd &xy)
 Projects a set of planar 2D points in world coordinates into image coordinates using a homography matrix.
 

Function Documentation

◆ projectPoints2()

template<typename T >
void industrial_calibration::projectPoints2 ( const T *const  camera_intr,
const T *const  pt_in_camera,
T *  pt_in_image 
)
Parameters
camera_intrCamera intrinsic parameters with distortion (size 9). See CalibCameraIntrinsics for details.
pt_in_camera3D point in the camera frame (size 3)
pt_in_image(Output) 2D image coordinates (size 2)

◆ calculateHomography()

Eigen::Matrix< double, 3, 3, Eigen::RowMajor > industrial_calibration::calculateHomography ( const Correspondence2D3D::Set  correspondences)

There is a 3x3 homography matrix, H, that can transform a point from one plane onto a different plane

\[
\left[ {\begin{array}{c}
u \\ v \\ 1 \\
\end{array} } \right]
= k *
\left[ {\begin{array}{ccc}
H_{00} & H_{01} & H_{02} \\
H_{10} & H_{11} & H_{12} \\
H_{20} & H_{21} & 1 \\
\end{array} } \right]
*
\left[ {\begin{array}{c}
x \\  y \\ 1 \\
\end{array} } \right]
\]

In our case we have 2 sets of known corresponding planar points: points on the planar target, and points in the image plane. Therefore, there is some matrix, H, which can transform target points into the image plane. If the target points and camera points actually match, we should be able to:

  1. Calculate H for a subset of corresponding points
  2. Transform the remaining target points by H to obtain estimates of their locations in the image plane
  3. Compare the calculated estimations to the actual image points to make sure they are very close. If they are not close, we know that the correspondences are not valid

The matrix H has 8 unique values. These 8 values of the homography matrix can be solved for, given a set of (at least) 8 corresponding planar vectors, by rearranging the above equations:

$ A * H = b $, where $ H = inv(A) * b $

  • A is matrix (size 2*n x 8), where n is the number of corresponding vectors
  • H is a vector (size 8 x 1) of the unknown elements of the homography matrix
  • B is a vector (size 2*n x 1) representing the elements of one set of planar vectors

\[
\left[ {\begin{array}{cccccccc}
-x_{i} & -y_{i} & -1 & 0 & 0 & 0 & u_{i}x_{i} & u_{i}y_{i} \\
0 & 0 & 0 & -x_{i} & -y_{i} & -1 & v_{i}x_{i} & v_{i}y_{i} \\
... & ... & ... & ... & ... & ... & ... & ... \\
-x_{n} & -y_{n} & -1 & 0 & 0 & 0 & u_{n}x_{n} & u_{n}y_{n} \\
0 & 0 & 0 & -x_{n} & -y_{n} & -1 & v_{n}x_{n} & v_{n}y_{n} \\
\end{array} } \right]
*
\left[ {\begin{array}{c}
H_{00} \\ H_{01} \\ H_{02} \\ H_{10} \\ H_{11} \\ H_{12} \\ H_{20} \\ H_{21} \\
\end{array} } \right]
=
\left[ {\begin{array}{c}
-u_{i} \\ -v_{i} \\ ... \\ ... \\ -u_{n} \\ -v_{n}
\end{array} } \right] \]

Note
At least 4 correspondences are required (2 equations per correspondence x 4 correspondences = 8 unknowns)

◆ projectHomography()

Eigen::Matrix2Xd industrial_calibration::projectHomography ( const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > &  H,
const Eigen::Matrix2Xd &  xy 
)
Parameters
HHomography matrix
xy2D planar points in world coordinates