CamBase.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_CORE_CAM_BASE_H
23 #define OV_CORE_CAM_BASE_H
24 
25 #include <Eigen/Eigen>
26 #include <unordered_map>
27 
28 #include <opencv2/opencv.hpp>
29 
30 namespace ov_core {
31 
39 class CamBase {
40 
41 public:
47  CamBase(int width, int height) : _width(width), _height(height) {}
48 
49  virtual ~CamBase() {}
50 
56  virtual void set_value(const Eigen::MatrixXd &calib) {
57 
58  // Assert we are of size eight
59  assert(calib.rows() == 8);
60  camera_values = calib;
61 
62  // Camera matrix
63  cv::Matx33d tempK;
64  tempK(0, 0) = calib(0);
65  tempK(0, 1) = 0;
66  tempK(0, 2) = calib(2);
67  tempK(1, 0) = 0;
68  tempK(1, 1) = calib(1);
69  tempK(1, 2) = calib(3);
70  tempK(2, 0) = 0;
71  tempK(2, 1) = 0;
72  tempK(2, 2) = 1;
73  camera_k_OPENCV = tempK;
74 
75  // Distortion parameters
76  cv::Vec4d tempD;
77  tempD(0) = calib(4);
78  tempD(1) = calib(5);
79  tempD(2) = calib(6);
80  tempD(3) = calib(7);
81  camera_d_OPENCV = tempD;
82  }
83 
89  virtual Eigen::Vector2f undistort_f(const Eigen::Vector2f &uv_dist) = 0;
90 
96  Eigen::Vector2d undistort_d(const Eigen::Vector2d &uv_dist) {
97  Eigen::Vector2f ept1, ept2;
98  ept1 = uv_dist.cast<float>();
99  ept2 = undistort_f(ept1);
100  return ept2.cast<double>();
101  }
102 
108  cv::Point2f undistort_cv(const cv::Point2f &uv_dist) {
109  Eigen::Vector2f ept1, ept2;
110  ept1 << uv_dist.x, uv_dist.y;
111  ept2 = undistort_f(ept1);
112  cv::Point2f pt_out;
113  pt_out.x = ept2(0);
114  pt_out.y = ept2(1);
115  return pt_out;
116  }
117 
123  virtual Eigen::Vector2f distort_f(const Eigen::Vector2f &uv_norm) = 0;
124 
130  Eigen::Vector2d distort_d(const Eigen::Vector2d &uv_norm) {
131  Eigen::Vector2f ept1, ept2;
132  ept1 = uv_norm.cast<float>();
133  ept2 = distort_f(ept1);
134  return ept2.cast<double>();
135  }
136 
142  cv::Point2f distort_cv(const cv::Point2f &uv_norm) {
143  Eigen::Vector2f ept1, ept2;
144  ept1 << uv_norm.x, uv_norm.y;
145  ept2 = distort_f(ept1);
146  cv::Point2f pt_out;
147  pt_out.x = ept2(0);
148  pt_out.y = ept2(1);
149  return pt_out;
150  }
151 
158  virtual void compute_distort_jacobian(const Eigen::Vector2d &uv_norm, Eigen::MatrixXd &H_dz_dzn, Eigen::MatrixXd &H_dz_dzeta) = 0;
159 
161  Eigen::MatrixXd get_value() { return camera_values; }
162 
164  cv::Matx33d get_K() { return camera_k_OPENCV; }
165 
167  cv::Vec4d get_D() { return camera_d_OPENCV; }
168 
170  int w() { return _width; }
171 
173  int h() { return _height; }
174 
175 protected:
176  // Cannot construct the base camera class, needs a distortion model
177  CamBase() = default;
178 
180  Eigen::MatrixXd camera_values;
181 
183  cv::Matx33d camera_k_OPENCV;
184 
186  cv::Vec4d camera_d_OPENCV;
187 
189  int _width;
190 
192  int _height;
193 };
194 
195 } // namespace ov_core
196 
197 #endif /* OV_CORE_CAM_BASE_H */
ov_core::CamBase::undistort_cv
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...
Definition: CamBase.h:108
ov_core::CamBase::~CamBase
virtual ~CamBase()
Definition: CamBase.h:49
ov_core::CamBase::get_D
cv::Vec4d get_D()
Gets the camera distortion.
Definition: CamBase.h:167
ov_core::CamBase::undistort_d
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...
Definition: CamBase.h:96
ov_core::CamBase::_width
int _width
Width of the camera (raw pixels)
Definition: CamBase.h:189
ov_core::CamBase::CamBase
CamBase(int width, int height)
Default constructor.
Definition: CamBase.h:47
ov_core::CamBase::distort_f
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.
ov_core::CamBase::compute_distort_jacobian
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.
ov_core::CamBase
Base pinhole camera model class.
Definition: CamBase.h:39
ov_core::CamBase::undistort_f
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...
ov_core::CamBase::camera_d_OPENCV
cv::Vec4d camera_d_OPENCV
Camera distortion in OpenCV format.
Definition: CamBase.h:186
ov_core::CamBase::set_value
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...
Definition: CamBase.h:56
ov_core::CamBase::distort_d
Eigen::Vector2d distort_d(const Eigen::Vector2d &uv_norm)
Given a normalized uv coordinate this will distort it to the raw image plane.
Definition: CamBase.h:130
ov_core::CamBase::camera_k_OPENCV
cv::Matx33d camera_k_OPENCV
Camera intrinsics in OpenCV format.
Definition: CamBase.h:183
ov_core::CamBase::_height
int _height
Height of the camera (raw pixels)
Definition: CamBase.h:192
ov_core::CamBase::CamBase
CamBase()=default
ov_core::CamBase::distort_cv
cv::Point2f distort_cv(const cv::Point2f &uv_norm)
Given a normalized uv coordinate this will distort it to the raw image plane.
Definition: CamBase.h:142
ov_core::CamBase::h
int h()
Gets the height of the camera images.
Definition: CamBase.h:173
ov_core::CamBase::get_K
cv::Matx33d get_K()
Gets the camera matrix.
Definition: CamBase.h:164
ov_core::CamBase::w
int w()
Gets the width of the camera images.
Definition: CamBase.h:170
ov_core::CamBase::get_value
Eigen::MatrixXd get_value()
Gets the complete intrinsic vector.
Definition: CamBase.h:161
ov_core::CamBase::camera_values
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)
Definition: CamBase.h:180
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30


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