Go to the documentation of this file.
22 #ifndef OV_CORE_CAM_BASE_H
23 #define OV_CORE_CAM_BASE_H
25 #include <Eigen/Eigen>
26 #include <unordered_map>
28 #include <opencv2/opencv.hpp>
56 virtual void set_value(
const Eigen::MatrixXd &calib) {
59 assert(calib.rows() == 8);
64 tempK(0, 0) = calib(0);
66 tempK(0, 2) = calib(2);
68 tempK(1, 1) = calib(1);
69 tempK(1, 2) = calib(3);
89 virtual Eigen::Vector2f
undistort_f(
const Eigen::Vector2f &uv_dist) = 0;
97 Eigen::Vector2f ept1, ept2;
98 ept1 = uv_dist.cast<
float>();
100 return ept2.cast<
double>();
109 Eigen::Vector2f ept1, ept2;
110 ept1 << uv_dist.x, uv_dist.y;
123 virtual Eigen::Vector2f
distort_f(
const Eigen::Vector2f &uv_norm) = 0;
130 Eigen::Vector2d
distort_d(
const Eigen::Vector2d &uv_norm) {
131 Eigen::Vector2f ept1, ept2;
132 ept1 = uv_norm.cast<
float>();
134 return ept2.cast<
double>();
143 Eigen::Vector2f ept1, ept2;
144 ept1 << uv_norm.x, uv_norm.y;
158 virtual void compute_distort_jacobian(
const Eigen::Vector2d &uv_norm, Eigen::MatrixXd &H_dz_dzn, Eigen::MatrixXd &H_dz_dzeta) = 0;
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 coor...
cv::Vec4d get_D()
Gets the camera distortion.
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 coor...
int _width
Width of the camera (raw pixels)
CamBase(int width, int height)
Default constructor.
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.
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.
Base pinhole camera model class.
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 coor...
cv::Vec4d camera_d_OPENCV
Camera distortion in OpenCV format.
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 cam...
Eigen::Vector2d distort_d(const Eigen::Vector2d &uv_norm)
Given a normalized uv coordinate this will distort it to the raw image plane.
cv::Matx33d camera_k_OPENCV
Camera intrinsics in OpenCV format.
int _height
Height of the camera (raw pixels)
cv::Point2f distort_cv(const cv::Point2f &uv_norm)
Given a normalized uv coordinate this will distort it to the raw image plane.
int h()
Gets the height of the camera images.
cv::Matx33d get_K()
Gets the camera matrix.
int w()
Gets the width of the camera images.
Eigen::MatrixXd get_value()
Gets the complete intrinsic vector.
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)
Core algorithms for OpenVINS.
ov_core
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17