MSCEqF 1.0
Multi State Constraint Equivariant Filter for visual inertial navigation
Loading...
Searching...
No Matches
msceqf::PinholeCamera Class Referenceabstract

This class represnt the base class for any pinhole camera type. More...

#include <camera.hpp>

Inheritance diagram for msceqf::PinholeCamera:

Public Member Functions

void undistort (std::vector< Eigen::Vector2f > &uv, const bool &normalize=false)
 Undistort given distorted point in Eigen format (std::vector<Eigen::Vector2f>)
 
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>)
 
virtual void undistortImage (const cv::Mat &image, cv::Mat &image_undistorted)=0
 Undistort given image in openCV format (cv::Mat)
 
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.
 

Protected Member Functions

 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
 
PinholeCameraoperator= (const PinholeCamera &)=delete
 
PinholeCameraoperator= (PinholeCamera &&)=delete
 

Protected Attributes

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.
 

Detailed Description

This class represnt the base class for any pinhole camera type.

Member Function Documentation

◆ denormalize() [1/4]

void msceqf::PinholeCamera::denormalize ( cv::Point2f & uv)

Denormalize multiple features uv coordinates in OpenCV format (cv::Point2f)

Parameters
uvuv coordinates

◆ denormalize() [2/4]

void msceqf::PinholeCamera::denormalize ( Eigen::Vector2f & uv)

Denormalize a single feature uv coordinates in Eigen format (Eigen::Vector2f)

Parameters
uvuv coordinates

◆ denormalize() [3/4]

void msceqf::PinholeCamera::denormalize ( std::vector< cv::Point2f > & uv)

Denormalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>)

Parameters
uvuv coordinates

◆ denormalize() [4/4]

void msceqf::PinholeCamera::denormalize ( std::vector< Eigen::Vector2f > & uv)

Denormalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>)

Parameters
uvuv coordinates

◆ distortionCoefficients()

const VectorX & msceqf::PinholeCamera::distortionCoefficients ( ) const

Get camera distortion coefficients (k1, k2, p1, p2, ...) as a vector.

Returns
Vector of distortion coefficients (k1, k2, p1, p2, ...)

◆ intrinsics()

const Vector4 & msceqf::PinholeCamera::intrinsics ( ) const

Get camera intrinsics parameter (fx, fy, cx, cy) as a 4 vector.

Returns
R4 vector representing the camera intrinsic parameters (fx, fy, cx, cy)

◆ normalize() [1/4]

void msceqf::PinholeCamera::normalize ( cv::Point2f & uv)

Normalize multiple features uv coordinates in OpenCV format (cv::Point2f)

Parameters
uvuv coordinates

◆ normalize() [2/4]

void msceqf::PinholeCamera::normalize ( Eigen::Vector2f & uv)

Normalize a single feature uv coordinates in Eigen format (Eigen::Vector2f)

Parameters
uvuv coordinates

◆ normalize() [3/4]

void msceqf::PinholeCamera::normalize ( std::vector< cv::Point2f > & uv)

Normalize multiple features uv coordinates in OpenCV format (std::vector<cv::Point2f>)

Parameters
uvuv coordinates

◆ normalize() [4/4]

void msceqf::PinholeCamera::normalize ( std::vector< Eigen::Vector2f > & uv)

Normalize multiple features uv coordinates in Eigen format (std::vector<Eigen::Vector2f>)

Parameters
uvuv coordinates

◆ setIntrinsics()

void msceqf::PinholeCamera::setIntrinsics ( const Vector4 & intrinsics)

Set the value of the intrinsic parameters.

Parameters
intrinsicsR4 vector representing the camera intrinsic parameters (fx, fy, cx, cy)

◆ undistort() [1/2]

virtual void msceqf::PinholeCamera::undistort ( std::vector< cv::Point2f > & uv_cv,
const bool & normalize = false )
pure virtual

Undistort given distorted point in OpenCV format (std::vector<cv::Point2f>)

Parameters
uv_cvuv coordinates
normalizeflag to decide wether normalize coordinates or not

Implemented in msceqf::EquidistantCamera, and msceqf::RadtanCamera.

◆ undistort() [2/2]

void msceqf::PinholeCamera::undistort ( std::vector< Eigen::Vector2f > & uv,
const bool & normalize = false )

Undistort given distorted point in Eigen format (std::vector<Eigen::Vector2f>)

Parameters
uvuv coordinates
normalizeFlag to decide wether normalize coordinates or not

◆ undistortImage()

virtual void msceqf::PinholeCamera::undistortImage ( const cv::Mat & image,
cv::Mat & image_undistorted )
pure virtual

Undistort given image in openCV format (cv::Mat)

Parameters
imageImage to be undistorted
image_undistortedUndistorted image

Implemented in msceqf::EquidistantCamera, and msceqf::RadtanCamera.


The documentation for this class was generated from the following file: