Calibration of a camera with radial distortion.  
 More...
#include <Cal3DS2_Base.h>
|  | 
| constexpr static auto | dimension = 9 | 
|  | shared pointer to stereo calibration object  More... 
 | 
|  | 
| constexpr static auto | dimension = 5 | 
|  | shared pointer to calibration object  More... 
 | 
|  | 
|  | 
| double | k1 () const | 
|  | First distortion coefficient.  More... 
 | 
|  | 
| double | k2 () const | 
|  | Second distortion coefficient.  More... 
 | 
|  | 
| double | p1 () const | 
|  | First tangential distortion coefficient.  More... 
 | 
|  | 
| double | p2 () const | 
|  | Second tangential distortion coefficient.  More... 
 | 
|  | 
| Vector4 | k () const | 
|  | return distortion parameter vector  More... 
 | 
|  | 
| Vector9 | vector () const | 
|  | Return all parameters as a vector.  More... 
 | 
|  | 
| Point2 | uncalibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const | 
|  | 
| Point2 | calibrate (const Point2 &p, OptionalJacobian< 2, 9 > Dcal={}, OptionalJacobian< 2, 2 > Dp={}) const | 
|  | Convert (distorted) image coordinates uv to intrinsic coordinates xy.  More... 
 | 
|  | 
| Matrix2 | D2d_intrinsic (const Point2 &p) const | 
|  | Derivative of uncalibrate wrpt intrinsic coordinates.  More... 
 | 
|  | 
| Matrix29 | D2d_calibration (const Point2 &p) const | 
|  | Derivative of uncalibrate wrpt the calibration parameters.  More... 
 | 
|  | 
| size_t | dim () const override | 
|  | return DOF, dimensionality of tangent space  More... 
 | 
|  | 
| static size_t | Dim () | 
|  | return DOF, dimensionality of tangent space  More... 
 | 
|  | 
Calibration of a camera with radial distortion. 
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̂ 
Definition at line 42 of file Cal3DS2_Base.h.
◆ shared_ptr
◆ Cal3DS2_Base() [1/3]
  
  | 
        
          | gtsam::Cal3DS2_Base::Cal3DS2_Base | ( |  | ) |  |  | default | 
 
Default Constructor with only unit focal length. 
 
 
◆ Cal3DS2_Base() [2/3]
  
  | 
        
          | gtsam::Cal3DS2_Base::Cal3DS2_Base | ( | double | fx, |  
          |  |  | double | fy, |  
          |  |  | double | s, |  
          |  |  | double | u0, |  
          |  |  | double | v0, |  
          |  |  | double | k1, |  
          |  |  | double | k2, |  
          |  |  | double | p1 = 0.0, |  
          |  |  | double | p2 = 0.0, |  
          |  |  | double | tol = 1e-5 |  
          |  | ) |  |  |  | inline | 
 
 
◆ ~Cal3DS2_Base()
  
  | 
        
          | gtsam::Cal3DS2_Base::~Cal3DS2_Base | ( |  | ) |  |  | inlineoverride | 
 
 
◆ Cal3DS2_Base() [3/3]
  
  | 
        
          | gtsam::Cal3DS2_Base::Cal3DS2_Base | ( | const Vector9 & | v | ) |  |  | inline | 
 
 
◆ calibrate()
Convert (distorted) image coordinates uv to intrinsic coordinates xy. 
Definition at line 133 of file Cal3DS2_Base.cpp.
 
 
◆ clone()
  
  | 
        
          | virtual std::shared_ptr<Cal3DS2_Base> gtsam::Cal3DS2_Base::clone | ( |  | ) | const |  | inlinevirtual | 
 
 
◆ D2d_calibration()
      
        
          | Matrix29 gtsam::Cal3DS2_Base::D2d_calibration | ( | const Point2 & | p | ) | const | 
      
 
Derivative of uncalibrate wrpt the calibration parameters. 
Definition at line 180 of file Cal3DS2_Base.cpp.
 
 
◆ D2d_intrinsic()
      
        
          | Matrix2 gtsam::Cal3DS2_Base::D2d_intrinsic | ( | const Point2 & | p | ) | const | 
      
 
Derivative of uncalibrate wrpt intrinsic coordinates. 
Definition at line 169 of file Cal3DS2_Base.cpp.
 
 
◆ Dim()
  
  | 
        
          | static size_t gtsam::Cal3DS2_Base::Dim | ( |  | ) |  |  | inlinestatic | 
 
return DOF, dimensionality of tangent space 
Definition at line 142 of file Cal3DS2_Base.h.
 
 
◆ dim()
  
  | 
        
          | size_t gtsam::Cal3DS2_Base::dim | ( |  | ) | const |  | inlineoverridevirtual | 
 
 
◆ equals()
      
        
          | bool gtsam::Cal3DS2_Base::equals | ( | const Cal3DS2_Base & | K, | 
        
          |  |  | double | tol = 1e-8 | 
        
          |  | ) |  | const | 
      
 
 
◆ k()
  
  | 
        
          | Vector4 gtsam::Cal3DS2_Base::k | ( |  | ) | const |  | inline | 
 
 
◆ k1()
  
  | 
        
          | double gtsam::Cal3DS2_Base::k1 | ( |  | ) | const |  | inline | 
 
 
◆ k2()
  
  | 
        
          | double gtsam::Cal3DS2_Base::k2 | ( |  | ) | const |  | inline | 
 
 
◆ p1()
  
  | 
        
          | double gtsam::Cal3DS2_Base::p1 | ( |  | ) | const |  | inline | 
 
First tangential distortion coefficient. 
Definition at line 107 of file Cal3DS2_Base.h.
 
 
◆ p2()
  
  | 
        
          | double gtsam::Cal3DS2_Base::p2 | ( |  | ) | const |  | inline | 
 
Second tangential distortion coefficient. 
Definition at line 110 of file Cal3DS2_Base.h.
 
 
◆ print()
  
  | 
        
          | void gtsam::Cal3DS2_Base::print | ( | const std::string & | s = "" | ) | const |  | overridevirtual | 
 
 
◆ uncalibrate()
convert intrinsic coordinates xy to (distorted) image coordinates uv 
- Parameters
- 
  
    | p | point in intrinsic coordinates |  | Dcal | optional 2*9 Jacobian wrpt Cal3DS2 parameters |  | Dp | optional 2*2 Jacobian wrpt intrinsic coordinates |  
 
- Returns
- point in (distorted) image coordinates 
Definition at line 94 of file Cal3DS2_Base.cpp.
 
 
◆ vector()
      
        
          | Vector9 gtsam::Cal3DS2_Base::vector | ( |  | ) | const | 
      
 
 
◆ operator<<
  
  | 
        
          | GTSAM_EXPORT friend std::ostream& operator<< | ( | std::ostream & | os, |  
          |  |  | const Cal3DS2_Base & | cal |  
          |  | ) |  |  |  | friend | 
 
 
◆ dimension
  
  | 
        
          | constexpr static auto gtsam::Cal3DS2_Base::dimension = 9 |  | inlinestaticconstexpr | 
 
shared pointer to stereo calibration object 
Definition at line 49 of file Cal3DS2_Base.h.
 
 
◆ k1_
  
  | 
        
          | double gtsam::Cal3DS2_Base::k1_ = 0.0f |  | protected | 
 
 
◆ k2_
  
  | 
        
          | double gtsam::Cal3DS2_Base::k2_ = 0.0f |  | protected | 
 
 
◆ p1_
  
  | 
        
          | double gtsam::Cal3DS2_Base::p1_ = 0.0f |  | protected | 
 
 
◆ p2_
  
  | 
        
          | double gtsam::Cal3DS2_Base::p2_ = 0.0f |  | protected | 
 
 
◆ tol_
  
  | 
        
          | double gtsam::Cal3DS2_Base::tol_ = 1e-5 |  | protected | 
 
 
The documentation for this class was generated from the following files: