![]() |
MSCEqF 1.0
Multi State Constraint Equivariant Filter for visual inertial navigation
|
This class represent a pinhole camera with radtan distortion model. More...
#include <camera.hpp>
Public Member Functions | |
RadtanCamera (const CameraOptions &opts, const Vector4 &intrinsics) | |
void | undistort (std::vector< cv::Point2f > &uv_cv, const bool &normalize) override |
Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>) | |
void | undistortImage (const cv::Mat &image, cv::Mat &image_undistorted) override |
Undistort given image in openCV format (cv::Mat) | |
![]() | |
void | undistort (std::vector< Eigen::Vector2f > &uv, const bool &normalize=false) |
Undistort given distorted point in Eigen format (std::vector<Eigen::Vector2f>) | |
void | normalize (std::vector< Eigen::Vector2f > &uv) |
Normalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>) | |
void | normalize (std::vector< cv::Point2f > &uv) |
Normalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>) | |
void | normalize (Eigen::Vector2f &uv) |
Normalize a single feature uv coordinates in Eigen format (Eigen::Vector2f) | |
void | normalize (cv::Point2f &uv) |
Normalize multiple features uv coordinates in OpenCV format (cv::Point2f) | |
void | denormalize (std::vector< Eigen::Vector2f > &uv) |
Denormalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>) | |
void | denormalize (std::vector< cv::Point2f > &uv) |
Denormalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>) | |
void | denormalize (Eigen::Vector2f &uv) |
Denormalize a single feature uv coordinates in Eigen format (Eigen::Vector2f) | |
void | denormalize (cv::Point2f &uv) |
Denormalize 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. | |
const VectorX & | distortionCoefficients () const |
Get camera distortion coefficients (k1, k2, p1, p2, ...) as a vector. | |
Additional Inherited Members | |
![]() | |
PinholeCamera (const VectorX &distortion_coefficients, const Vector4 instrinsics, const uint &width, const uint &height) | |
PinholeCamera ()=delete | |
Rule of Five. | |
PinholeCamera (const PinholeCamera &)=delete | |
PinholeCamera (PinholeCamera &&)=delete | |
PinholeCamera & | operator= (const PinholeCamera &)=delete |
PinholeCamera & | operator= (PinholeCamera &&)=delete |
![]() | |
VectorX | distortion_coefficients_ |
Vector of distortion coefficients (k1, k2, p1, p2, ...) | |
Vector4 | intrinsics_ |
Vector of intrinsic paramater (fx, fy, cx, cy) | |
uint | width_ |
Image width. | |
uint | height_ |
Image height. | |
This class represent a pinhole camera with radtan distortion model.
|
overridevirtual |
Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>)
uv_cv | uv coordinates |
normalize | Flag to decide wether normalize coordinates or not |
Implements msceqf::PinholeCamera.
|
overridevirtual |
Undistort given image in openCV format (cv::Mat)
image | Image to be undistorted |
image_undistorted | Undistorted image |
Implements msceqf::PinholeCamera.