Fisheye / equadistant model pinhole camera model class. More...
#include <CamEqui.h>

Public Member Functions | |
| CamEqui (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... | |
| ~CamEqui () | |
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... | |
Fisheye / equadistant model pinhole camera model class.
As fisheye or wide-angle lenses are widely used in practice, we here provide mathematical derivations of such distortion model as in OpenCV fisheye.
where
are the normalized coordinates of the 3D feature and u and v are the distorted image coordinates on the image plane. Clearly, the following distortion intrinsic parameters are used in the above model:
In analogy to the previous radial distortion (see ov_core::CamRadtan) case, the following Jacobian for these parameters is needed for intrinsic calibration:
Similarly, with the chain rule of differentiation, we can compute the following Jacobian with respect to the normalized coordinates:
To equate this to one of Kalibr's models, this is what you would use for pinhole-equi.
|
inline |
|
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.
|
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.
|
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.