Base pinhole camera model class. More...
#include <CamBase.h>
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... | |
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.
|
inline |
|
protecteddefault |
|
pure virtual |
Computes the derivative of raw distorted to normalized coordinate.
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 |
Implemented in ov_core::CamEqui, and ov_core::CamRadtan.
|
inline |
|
inline |
|
pure virtual |
Given a normalized uv coordinate this will distort it to the raw image plane.
uv_norm | Normalized coordinates we wish to distort |
Implemented in ov_core::CamEqui, and ov_core::CamRadtan.
|
inline |
|
inline |
|
inline |
|
inline |
|
inlinevirtual |
|
inline |
|
inline |
|
pure virtual |
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
uv_dist | Raw uv coordinate we wish to undistort |
Implemented in ov_core::CamEqui, and ov_core::CamRadtan.
|
inline |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |