MSCEqF 1.0
Multi State Constraint Equivariant Filter for visual inertial navigation
Loading...
Searching...
No Matches
camera.hpp
1// Copyright (C) 2023 Alessandro Fornasier.
2// Control of Networked Systems, University of Klagenfurt, Austria.
3//
4// All rights reserved.
5//
6// This software is licensed under the terms of the BSD-2-Clause-License with
7// no commercial use allowed, the full terms of which are made available
8// in the LICENSE file. No license in patents is granted.
9//
10// You can contact the authors at <alessandro.fornasier@ieee.org>
11
12#ifndef CAMERA_HPP
13#define CAMERA_HPP
14
15#include <memory>
16#include <opencv2/opencv.hpp>
17
18#include "msceqf/options/msceqf_options.hpp"
19#include "types/fptypes.hpp"
20
21namespace msceqf
22{
28{
29 public:
30 virtual ~PinholeCamera() = default;
31
38 void undistort(std::vector<Eigen::Vector2f>& uv, const bool& normalize = false);
39
46 virtual void undistort(std::vector<cv::Point2f>& uv_cv, const bool& normalize = false) = 0;
47
54 virtual void undistortImage(const cv::Mat& image, cv::Mat& image_undistorted) = 0;
55
61 void normalize(std::vector<Eigen::Vector2f>& uv);
62
68 void normalize(std::vector<cv::Point2f>& uv);
69
75 void normalize(Eigen::Vector2f& uv);
76
82 void normalize(cv::Point2f& uv);
83
89 void denormalize(std::vector<Eigen::Vector2f>& uv);
90
96 void denormalize(std::vector<cv::Point2f>& uv);
97
103 void denormalize(Eigen::Vector2f& uv);
104
110 void denormalize(cv::Point2f& uv);
111
117 void setIntrinsics(const Vector4& intrinsics);
118
124 const Vector4& intrinsics() const;
125
131 const VectorX& distortionCoefficients() const;
132
133 protected:
134 PinholeCamera(const VectorX& distortion_coefficients,
135 const Vector4 instrinsics,
136 const uint& width,
137 const uint& height);
138
140 PinholeCamera() = delete;
141 PinholeCamera(const PinholeCamera&) = delete;
142 PinholeCamera(PinholeCamera&&) = delete;
143 PinholeCamera& operator=(const PinholeCamera&) = delete;
144 PinholeCamera& operator=(PinholeCamera&&) = delete;
145
147 Vector4 intrinsics_;
148 uint width_;
149 uint height_;
150};
151
156struct RadtanCamera final : public PinholeCamera
157{
158 RadtanCamera(const CameraOptions& opts, const Vector4& intrinsics);
159
166 void undistort(std::vector<cv::Point2f>& uv_cv, const bool& normalize) override;
167
174 void undistortImage(const cv::Mat& image, cv::Mat& image_undistorted) override;
175};
176
177struct EquidistantCamera final : public PinholeCamera
178{
179 EquidistantCamera(const CameraOptions& opts, const Vector4& intrinsics);
180
187 void undistort(std::vector<cv::Point2f>& uv_cv, const bool& normalize) override;
188
195 void undistortImage(const cv::Mat& image, cv::Mat& image_undistorted) override;
196};
197
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>;
204
213template <typename T>
214[[nodiscard]] static PinholeCameraUniquePtr createCamera(const CameraOptions& opts, const Vector4& intrinsics)
215{
216 if constexpr (std::is_base_of_v<PinholeCamera, T>)
217 {
218 return std::make_unique<T>(opts, intrinsics);
219 }
220 else
221 {
222 return nullptr;
223 }
224}
225
226} // namespace msceqf
227
228#endif // CAMERA_HPP
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>)