Industrial Calibration  1.0.0
Loading...
Searching...
No Matches
Projection Analysis

Detailed Description

Functions

Eigen::Vector3d industrial_calibration::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 industrial_calibration::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 industrial_calibration::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 industrial_calibration::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.
 

Function Documentation

◆ computeLinePlaneIntersection()

Eigen::Vector3d industrial_calibration::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 
)
Parameters
plane_normalUnit normal vector defining the plane
plane_ptPoint on the plane
lineUnit vector defining the line
line_ptPoint on the line
epsilon

◆ project3D()

Eigen::MatrixX3d industrial_calibration::project3D ( const Eigen::MatrixX2d &  source,
const Eigen::Isometry3d &  source_to_plane,
const Eigen::Matrix3d &  k 
)
Parameters
sourceSet of 2D points
source_to_planeMatrix that transforms the source points into the frame of the plane (e.g., camera to target transform)
k3x3 camera projection matrix
Returns