Factor Catalog Reference
This chapter is a complete reference for all factor types (residual computations) supported by the optimization IR. Each factor defines a residual function connecting specific parameter blocks.
Reprojection Factors
All reprojection factors compute the weighted pixel residual:
They differ in the transform chain from world point to pixel.
ReprojPointPinhole4
Parameters: [intrinsics(4), pose(7)]
Transform chain: , then pinhole projection with intrinsics only (no distortion).
Use case: Distortion-free cameras or when distortion is handled externally.
ReprojPointPinhole4Dist5
Parameters: [intrinsics(4), distortion(5), pose(7)]
Transform chain: , then pinhole + Brown-Conrady distortion + intrinsics.
Use case: Standard single-camera calibration (planar intrinsics).
ReprojPointPinhole4Dist5Scheimpflug2
Parameters: [intrinsics(4), distortion(5), sensor(2), pose(7)]
Transform chain: , then pinhole + distortion + Scheimpflug tilt + intrinsics.
Use case: Laser profilers with tilted sensors.
ReprojPointPinhole4Dist5TwoSE3
Parameters: [intrinsics(4), distortion(5), extrinsics(7), rig_pose(7)]
Transform chain:
The camera pose is composed from two SE(3) transforms: the camera-to-rig extrinsics and the rig-to-target pose.
Use case: Multi-camera rig calibration.
ReprojPointPinhole4Dist5HandEye
Parameters: [intrinsics(4), distortion(5), extrinsics(7), handeye(7), target_pose(7)]
Per-residual data: robot_pose (, known from robot kinematics)
Transform chain (eye-in-hand):
Then project .
For single-camera hand-eye, .
Use case: Hand-eye calibration (camera on robot arm).
ReprojPointPinhole4Dist5HandEyeRobotDelta
Parameters: [intrinsics(4), distortion(5), extrinsics(7), handeye(7), target_pose(7), robot_delta(7)]
Per-residual data: robot_pose
Transform chain: Same as HandEye, but with a per-view SE(3) correction applied to the robot pose:
The correction is regularized by an Se3TangentPrior factor.
Use case: Hand-eye calibration with imprecise robot kinematics (accounts for robot pose uncertainty).
Laser Factors
Both laser factors have residual dimension 1 and connect [intrinsics(4), distortion(5), pose(7), plane(3+1)].
LaserPlanePixel
Computation:
- Undistort laser pixel to normalized coordinates
- Back-project to a ray in camera frame
- Intersect ray with target plane (known from pose)
- Compute 3D point in camera frame
- Measure signed distance from 3D point to laser plane
Residual: — distance in meters.
LaserLineDist2D
Computation:
- Compute 3D intersection line of laser plane and target plane (in camera frame)
- Project this line onto the normalized camera plane
- Undistort laser pixel to normalized coordinates
- Measure perpendicular distance from pixel to projected line (2D geometry)
- Scale by for pixel-comparable units
Residual: — distance in effective pixels.
Advantages over LaserPlanePixel: Undistortion done once per pixel (not per-iteration), residuals in pixel units (directly comparable to reprojection error), simpler 2D geometry.
Default: This is the recommended laser residual type.
Prior Factors
Se3TangentPrior
Parameters: [se3_param(7)]
Computation: Maps the SE(3) parameter to its tangent vector (via logarithm map) and divides by the prior standard deviations:
where is the 6D tangent vector.
Use case: Zero-mean Gaussian prior on SE(3) parameters. Applied to robot pose corrections (robot_delta) to penalize deviations from the nominal robot kinematics.
Effect: Adds a regularization term to the cost function.
Summary Table
| Factor | Params | Res. dim | Units | Domain |
|---|---|---|---|---|
| ReprojPointPinhole4 | 2 blocks | 2 | pixels | Simple pinhole |
| ReprojPointPinhole4Dist5 | 3 blocks | 2 | pixels | Standard calibration |
| ReprojPointPinhole4Dist5Scheimpflug2 | 4 blocks | 2 | pixels | Tilted sensor |
| ReprojPointPinhole4Dist5TwoSE3 | 4 blocks | 2 | pixels | Multi-camera rig |
| ReprojPointPinhole4Dist5HandEye | 5 blocks | 2 | pixels | Hand-eye |
| ReprojPointPinhole4Dist5HandEyeRobotDelta | 6 blocks | 2 | pixels | Hand-eye + robot refinement |
| LaserPlanePixel | 4 blocks | 1 | meters | Laser triangulation |
| LaserLineDist2D | 4 blocks | 1 | pixels | Laser triangulation |
| Se3TangentPrior | 1 block | 6 | normalized | Regularization |