Radial-tangential / Brown–Conrady model pinhole camera model class. More...
#include <CamRadtan.h>
Public Member Functions | |
CamRadtan (int width, int height) | |
Default constructor. More... | |
void | compute_distort_jacobian (const Eigen::Vector2d &uv_norm, Eigen::MatrixXd &H_dz_dzn, Eigen::MatrixXd &H_dz_dzeta) override |
Computes the derivative of raw distorted to normalized coordinate. More... | |
Eigen::Vector2f | distort_f (const Eigen::Vector2f &uv_norm) override |
Given a normalized uv coordinate this will distort it to the raw image plane. More... | |
Eigen::Vector2f | undistort_f (const Eigen::Vector2f &uv_dist) override |
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More... | |
~CamRadtan () | |
Public Member Functions inherited from ov_core::CamBase | |
CamBase (int width, int height) | |
Default constructor. 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... | |
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... | |
int | w () |
Gets the width of the camera images. More... | |
virtual | ~CamBase () |
Additional Inherited Members | |
Protected Member Functions inherited from ov_core::CamBase | |
CamBase ()=default | |
Protected Attributes inherited from ov_core::CamBase | |
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... | |
Radial-tangential / Brown–Conrady model pinhole camera model class.
To calibrate camera intrinsics, we need to know how to map our normalized coordinates into the raw pixel coordinates on the image plane. We first employ the radial distortion as in OpenCV model:
where are the normalized coordinates of the 3D feature and u and v are the distorted image coordinates on the image plane. The following distortion and camera intrinsic (focal length and image center) parameters are involved in the above distortion model, which can be estimated online:
Note that we do not estimate the higher order (i.e., higher than fourth order) terms as in most offline calibration methods such as Kalibr. To estimate these intrinsic parameters (including the distortation parameters), the following Jacobian for these parameters is needed:
Similarly, the Jacobian with respect to the normalized coordinates can be obtained as follows:
To equate this camera class to Kalibr's models, this is what you would use for pinhole-radtan
.
Definition at line 82 of file CamRadtan.h.
|
inline |
Default constructor.
width | Width of the camera (raw pixels) |
height | Height of the camera (raw pixels) |
Definition at line 90 of file CamRadtan.h.
|
inline |
Definition at line 92 of file CamRadtan.h.
|
inlineoverridevirtual |
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 |
Implements ov_core::CamBase.
Definition at line 154 of file CamRadtan.h.
|
inlineoverridevirtual |
Given a normalized uv coordinate this will distort it to the raw image plane.
uv_norm | Normalized coordinates we wish to distort |
Implements ov_core::CamBase.
Definition at line 127 of file CamRadtan.h.
|
inlineoverridevirtual |
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 |
Implements ov_core::CamBase.
Definition at line 99 of file CamRadtan.h.