Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ov_core::CamBase Class Referenceabstract

Base pinhole camera model class. More...

#include <CamBase.h>

Inheritance diagram for ov_core::CamBase:
Inheritance graph
[legend]

Public Member Functions

 CamBase (int width, int height)
 Default constructor. More...
 
virtual void compute_distort_jacobian (const Eigen::Vector2d &uv_norm, Eigen::MatrixXd &H_dz_dzn, Eigen::MatrixXd &H_dz_dzeta)=0
 Computes the derivative of raw distorted to normalized coordinate. More...
 
cv::Point2f distort_cv (const cv::Point2f &uv_norm)
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
Eigen::Vector2d distort_d (const Eigen::Vector2d &uv_norm)
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
virtual Eigen::Vector2f distort_f (const Eigen::Vector2f &uv_norm)=0
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
cv::Vec4d get_D ()
 Gets the camera distortion. More...
 
cv::Matx33d get_K ()
 Gets the camera matrix. More...
 
Eigen::MatrixXd get_value ()
 Gets the complete intrinsic vector. More...
 
int h ()
 Gets the height of the camera images. More...
 
virtual void set_value (const Eigen::MatrixXd &calib)
 This will set and update the camera calibration values. This should be called on startup for each camera and after update! More...
 
cv::Point2f undistort_cv (const cv::Point2f &uv_dist)
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
Eigen::Vector2d undistort_d (const Eigen::Vector2d &uv_dist)
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
virtual Eigen::Vector2f undistort_f (const Eigen::Vector2f &uv_dist)=0
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
int w ()
 Gets the width of the camera images. More...
 
virtual ~CamBase ()
 

Protected Member Functions

 CamBase ()=default
 

Protected Attributes

int _height
 Height of the camera (raw pixels) More...
 
int _width
 Width of the camera (raw pixels) More...
 
cv::Vec4d camera_d_OPENCV
 Camera distortion in OpenCV format. More...
 
cv::Matx33d camera_k_OPENCV
 Camera intrinsics in OpenCV format. More...
 
Eigen::MatrixXd camera_values
 Raw set of camera intrinic values (f_x & f_y & c_x & c_y & k_1 & k_2 & k_3 & k_4) More...
 

Detailed Description

Base pinhole camera model class.

This is the base class for all our camera models. All these models are pinhole cameras, thus just have standard reprojection logic. See each derived class for detailed examples of each model.

Definition at line 39 of file CamBase.h.

Constructor & Destructor Documentation

◆ CamBase() [1/2]

ov_core::CamBase::CamBase ( int  width,
int  height 
)
inline

Default constructor.

Parameters
widthWidth of the camera (raw pixels)
heightHeight of the camera (raw pixels)

Definition at line 47 of file CamBase.h.

◆ ~CamBase()

virtual ov_core::CamBase::~CamBase ( )
inlinevirtual

Definition at line 49 of file CamBase.h.

◆ CamBase() [2/2]

ov_core::CamBase::CamBase ( )
protecteddefault

Member Function Documentation

◆ compute_distort_jacobian()

virtual void ov_core::CamBase::compute_distort_jacobian ( const Eigen::Vector2d &  uv_norm,
Eigen::MatrixXd &  H_dz_dzn,
Eigen::MatrixXd &  H_dz_dzeta 
)
pure virtual

Computes the derivative of raw distorted to normalized coordinate.

Parameters
uv_normNormalized coordinates we wish to distort
H_dz_dznDerivative of measurement z in respect to normalized
H_dz_dzetaDerivative of measurement z in respect to intrinic parameters

Implemented in ov_core::CamEqui, and ov_core::CamRadtan.

◆ distort_cv()

cv::Point2f ov_core::CamBase::distort_cv ( const cv::Point2f &  uv_norm)
inline

Given a normalized uv coordinate this will distort it to the raw image plane.

Parameters
uv_normNormalized coordinates we wish to distort
Returns
2d vector of raw uv coordinate

Definition at line 142 of file CamBase.h.

◆ distort_d()

Eigen::Vector2d ov_core::CamBase::distort_d ( const Eigen::Vector2d &  uv_norm)
inline

Given a normalized uv coordinate this will distort it to the raw image plane.

Parameters
uv_normNormalized coordinates we wish to distort
Returns
2d vector of raw uv coordinate

Definition at line 130 of file CamBase.h.

◆ distort_f()

virtual Eigen::Vector2f ov_core::CamBase::distort_f ( const Eigen::Vector2f &  uv_norm)
pure virtual

Given a normalized uv coordinate this will distort it to the raw image plane.

Parameters
uv_normNormalized coordinates we wish to distort
Returns
2d vector of raw uv coordinate

Implemented in ov_core::CamEqui, and ov_core::CamRadtan.

◆ get_D()

cv::Vec4d ov_core::CamBase::get_D ( )
inline

Gets the camera distortion.

Definition at line 167 of file CamBase.h.

◆ get_K()

cv::Matx33d ov_core::CamBase::get_K ( )
inline

Gets the camera matrix.

Definition at line 164 of file CamBase.h.

◆ get_value()

Eigen::MatrixXd ov_core::CamBase::get_value ( )
inline

Gets the complete intrinsic vector.

Definition at line 161 of file CamBase.h.

◆ h()

int ov_core::CamBase::h ( )
inline

Gets the height of the camera images.

Definition at line 173 of file CamBase.h.

◆ set_value()

virtual void ov_core::CamBase::set_value ( const Eigen::MatrixXd &  calib)
inlinevirtual

This will set and update the camera calibration values. This should be called on startup for each camera and after update!

Parameters
calibCamera calibration information (f_x & f_y & c_x & c_y & k_1 & k_2 & k_3 & k_4)

Definition at line 56 of file CamBase.h.

◆ undistort_cv()

cv::Point2f ov_core::CamBase::undistort_cv ( const cv::Point2f &  uv_dist)
inline

Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.

Parameters
uv_distRaw uv coordinate we wish to undistort
Returns
2d vector of normalized coordinates

Definition at line 108 of file CamBase.h.

◆ undistort_d()

Eigen::Vector2d ov_core::CamBase::undistort_d ( const Eigen::Vector2d &  uv_dist)
inline

Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.

Parameters
uv_distRaw uv coordinate we wish to undistort
Returns
2d vector of normalized coordinates

Definition at line 96 of file CamBase.h.

◆ undistort_f()

virtual Eigen::Vector2f ov_core::CamBase::undistort_f ( const Eigen::Vector2f &  uv_dist)
pure virtual

Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.

Parameters
uv_distRaw uv coordinate we wish to undistort
Returns
2d vector of normalized coordinates

Implemented in ov_core::CamEqui, and ov_core::CamRadtan.

◆ w()

int ov_core::CamBase::w ( )
inline

Gets the width of the camera images.

Definition at line 170 of file CamBase.h.

Member Data Documentation

◆ _height

int ov_core::CamBase::_height
protected

Height of the camera (raw pixels)

Definition at line 192 of file CamBase.h.

◆ _width

int ov_core::CamBase::_width
protected

Width of the camera (raw pixels)

Definition at line 189 of file CamBase.h.

◆ camera_d_OPENCV

cv::Vec4d ov_core::CamBase::camera_d_OPENCV
protected

Camera distortion in OpenCV format.

Definition at line 186 of file CamBase.h.

◆ camera_k_OPENCV

cv::Matx33d ov_core::CamBase::camera_k_OPENCV
protected

Camera intrinsics in OpenCV format.

Definition at line 183 of file CamBase.h.

◆ camera_values

Eigen::MatrixXd ov_core::CamBase::camera_values
protected

Raw set of camera intrinic values (f_x & f_y & c_x & c_y & k_1 & k_2 & k_3 & k_4)

Definition at line 180 of file CamBase.h.


The documentation for this class was generated from the following file:


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17