Classes
Geometry

Common base class for all calibration models. More...

Classes

class  gtsam::InvDepthCamera3< CALIBRATION >
 
class  gtsam::Pose3Upright
 

Detailed Description

Common base class for all calibration models.

A 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIONS is not defined, or as a quaternion if it is defined.

Calibration of a omni-directional camera with mirror + lens radial distortion.

Calibration of a fisheye camera.

Calibration of a camera with radial distortion.

Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimization.

Calibration used by Bundler.

The most common 5DOF 3D->2D calibration, stereo version.

The most common 5DOF 3D->2D calibration.

See also
Cal3DS2_Base

Uses same distortionmodel as OpenCV, with http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html but using only k1,k2,p1, and p2 coefficients. K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] r² = P.x² + P.y² P̂ = (1 + k1*r² + k2*r⁴) P + [ (2*p1 P.x P.y) + p2 (r² + 2 Pn.x²) p1 (r² + 2 Pn.y²) + (2*p2 Pn.x Pn.y) ] pi = K*P̂

Uses same distortionmodel as OpenCV, with https://docs.opencv.org/master/db/d58/group__calib3d__fisheye.html 3D point in camera frame p = (x, y, z) Intrinsic coordinates: [x_i;y_i] = [x/z; y/z] Distorted coordinates: r² = (x_i)² + (y_i)² th = atan(r) th_d = th(1 + k1*th² + k2*th⁴ + k3*th⁶ + k4*th⁸) [x_d; y_d] = (th_d / r)*[x_i; y_i] Pixel coordinates: K = [fx s u0; 0 fy v0 ;0 0 1] [u; v; 1] = K*[x_d; y_d; 1]

Similar to Cal3DS2, does distortion but has additional mirror parameter xi K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] Pn = [ P.x / (1 + xi * {P.x² + P.y² + 1}), P.y / (1 + xi * {P.x² + P.y² + 1})] r² = Pn.x² + Pn.y² {pn} = (1 + k1*r² + k2*r⁴ ) pn + [ 2*k3 pn.x pn.y + k4 (r² + 2 Pn.x²) ; k3 (rr + 2 Pn.y²) + 2*k4 pn.x pn.y ] pi = K*pn

A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras

A Calibrated camera class [R|-R't], calibration K=I. If calibration is known, it is more computationally efficient to calibrate the measurements rather than try to predict in pixels.

A 3D line (R,a,b) : (Rot3,Scalar,Scalar)

A pinhole camera class that has a Pose3 and a Calibration. Use PinholePose if you will not be optimizing for Calibration

A pinhole camera class that has a Pose3 and a fixed Calibration.

A pinhole camera class that has a Pose3 and a fixed Calibration. Instead of using this class, one might consider calibrating the measurements and using CalibratedCamera, which would then be faster.

A 2D pose (Point2,Rot2)

A 3D pose (R,t) : (Rot3,Point3)

Rotation matrix NOTE: the angle theta is in radians unless explicitly stated

A stereo camera class, parameterize by left camera pose and stereo calibration

A 2D stereo point, v will be same for rectified images



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:44