ov_core::CamBase class

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.

Derived classes

class CamEqui
Fisheye / equadistant model pinhole camera model class.
class CamRadtan
Radial-tangential / Brown–Conrady model pinhole camera model class.

Constructors, destructors, conversion operators

CamBase(int width, int height)
Default constructor.

Public functions

void set_value(const Eigen::MatrixXd& calib) virtual
This will set and update the camera calibration values. This should be called on startup for each camera and after update!
auto undistort_f(const Eigen::Vector2f& uv_dist) -> Eigen::Vector2f pure virtual
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
auto undistort_d(const Eigen::Vector2d& uv_dist) -> Eigen::Vector2d
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
auto undistort_cv(const cv::Point2f& uv_dist) -> cv::Point2f
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
auto distort_f(const Eigen::Vector2f& uv_norm) -> Eigen::Vector2f pure virtual
Given a normalized uv coordinate this will distort it to the raw image plane.
auto distort_d(const Eigen::Vector2d& uv_norm) -> Eigen::Vector2d
Given a normalized uv coordinate this will distort it to the raw image plane.
auto distort_cv(const cv::Point2f& uv_norm) -> cv::Point2f
Given a normalized uv coordinate this will distort it to the raw image plane.
void 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.
auto get_value() -> Eigen::MatrixXd
Gets the complete intrinsic vector.
auto get_K() -> cv::Matx33d
Gets the camera matrix.
auto get_D() -> cv::Vec4d
Gets the camera distortion.
auto w() -> int
Gets the width of the camera images.
auto h() -> int
Gets the height of the camera images.

Protected variables

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)
cv::Matx33d camera_k_OPENCV
Camera intrinsics in OpenCV format.
cv::Vec4d camera_d_OPENCV
Camera distortion in OpenCV format.
int _width
Width of the camera (raw pixels)
int _height
Height of the camera (raw pixels)

Function documentation

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

Default constructor.

Parameters
width Width of the camera (raw pixels)
height Height of the camera (raw pixels)

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

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

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

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_dist Raw uv coordinate we wish to undistort
Returns 2d vector of normalized coordinates

Eigen::Vector2d ov_core::CamBase::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.

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

cv::Point2f ov_core::CamBase::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.

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

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_norm Normalized coordinates we wish to distort
Returns 2d vector of raw uv coordinate

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

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

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

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

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

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

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_norm Normalized coordinates we wish to distort
H_dz_dzn Derivative of measurement z in respect to normalized
H_dz_dzeta Derivative of measurement z in respect to intrinic parameters