16#include <opencv2/opencv.hpp>
18#include "msceqf/options/msceqf_options.hpp"
19#include "types/fptypes.hpp"
54 virtual void undistortImage(
const cv::Mat& image, cv::Mat& image_undistorted) = 0;
135 const Vector4 instrinsics,
198using PinholeCameraSharedPtr = std::shared_ptr<PinholeCamera>;
199using PinholeCameraUniquePtr = std::unique_ptr<PinholeCamera>;
200using RadtanCameraSharedPtr = std::shared_ptr<RadtanCamera>;
201using RadtanCameraUniquePtr = std::unique_ptr<RadtanCamera>;
202using EquidistantCameraSharedPtr = std::shared_ptr<EquidistantCamera>;
203using EquidistantCameraUniquePtr = std::unique_ptr<EquidistantCamera>;
214[[nodiscard]]
static PinholeCameraUniquePtr createCamera(
const CameraOptions& opts,
const Vector4& intrinsics)
216 if constexpr (std::is_base_of_v<PinholeCamera, T>)
218 return std::make_unique<T>(opts, intrinsics);
This class represnt the base class for any pinhole camera type.
Definition camera.hpp:28
virtual void undistort(std::vector< cv::Point2f > &uv_cv, const bool &normalize=false)=0
Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>)
void normalize(cv::Point2f &uv)
Normalize multiple features uv coordinates in OpenCV format (cv::Point2f)
void setIntrinsics(const Vector4 &intrinsics)
Set the value of the intrinsic parameters.
const Vector4 & intrinsics() const
Get camera intrinsics parameter (fx, fy, cx, cy) as a 4 vector.
uint height_
Image height.
Definition camera.hpp:149
void denormalize(std::vector< cv::Point2f > &uv)
Denormalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>)
const VectorX & distortionCoefficients() const
Get camera distortion coefficients (k1, k2, p1, p2, ...) as a vector.
void normalize(std::vector< Eigen::Vector2f > &uv)
Normalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>)
PinholeCamera()=delete
Rule of Five.
virtual void undistortImage(const cv::Mat &image, cv::Mat &image_undistorted)=0
Undistort given image in openCV format (cv::Mat)
uint width_
Image width.
Definition camera.hpp:148
void normalize(std::vector< cv::Point2f > &uv)
Normalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>)
void denormalize(std::vector< Eigen::Vector2f > &uv)
Denormalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>)
void normalize(Eigen::Vector2f &uv)
Normalize a single feature uv coordinates in Eigen format (Eigen::Vector2f)
void undistort(std::vector< Eigen::Vector2f > &uv, const bool &normalize=false)
Undistort given distorted point in Eigen format (std::vector<Eigen::Vector2f>)
void denormalize(Eigen::Vector2f &uv)
Denormalize a single feature uv coordinates in Eigen format (Eigen::Vector2f)
Vector4 intrinsics_
Vector of intrinsic paramater (fx, fy, cx, cy)
Definition camera.hpp:147
void denormalize(cv::Point2f &uv)
Denormalize multiple features uv coordinates in OpenCV format (cv::Point2f)
VectorX distortion_coefficients_
Vector of distortion coefficients (k1, k2, p1, p2, ...)
Definition camera.hpp:146
Definition msceqf_options.hpp:161
Definition camera.hpp:178
void undistortImage(const cv::Mat &image, cv::Mat &image_undistorted) override
Undistort given image in openCV format (cv::Mat)
void undistort(std::vector< cv::Point2f > &uv_cv, const bool &normalize) override
Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>)
This class represent a pinhole camera with radtan distortion model.
Definition camera.hpp:157
void undistortImage(const cv::Mat &image, cv::Mat &image_undistorted) override
Undistort given image in openCV format (cv::Mat)
void undistort(std::vector< cv::Point2f > &uv_cv, const bool &normalize) override
Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>)