class
CamRadtanRadial-tangential / Brown–Conrady model pinhole camera model class.
Contents
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
.
Base classes
- class CamBase
- Base pinhole camera model class.
Constructors, destructors, conversion operators
- CamRadtan(int width, int height)
- Default constructor.
Public functions
- auto undistort_f(const Eigen::Vector2f& uv_dist) -> Eigen::Vector2f override
- Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
- auto distort_f(const Eigen::Vector2f& uv_norm) -> Eigen::Vector2f override
- Given a normalized uv coordinate this will distort it to the raw image plane.
- 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.
Function documentation
ov_core:: CamRadtan:: CamRadtan(int width,
int height)
Default constructor.
Parameters | |
---|---|
width | Width of the camera (raw pixels) |
height | Height of the camera (raw pixels) |
Eigen::Vector2f ov_core:: CamRadtan:: 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.
Parameters | |
---|---|
uv_dist | Raw uv coordinate we wish to undistort |
Returns | 2d vector of normalized coordinates |
Eigen::Vector2f ov_core:: CamRadtan:: distort_f(const Eigen::Vector2f& uv_norm) override
Given a normalized uv coordinate this will distort it to the raw image plane.
Parameters | |
---|---|
uv_norm | Normalized coordinates we wish to distort |
Returns | 2d vector of raw uv coordinate |
void ov_core:: CamRadtan:: 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.
Parameters | |
---|---|
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 |