SaDVIO
Public Member Functions | List of all members
isae::DoubleSphere Class Reference

An image sensor class that uses a double sphere model. More...

#include <DoubleSphere.h>

Inheritance diagram for isae::DoubleSphere:
Inheritance graph
[legend]
Collaboration diagram for isae::DoubleSphere:
Collaboration graph
[legend]

Public Member Functions

 DoubleSphere (const cv::Mat &image, Eigen::Matrix3d K, double alpha, double xi)
 
bool project (const Eigen::Affine3d &T_w_lmk, const std::shared_ptr< AModel3d > ldmk_model, std::vector< Eigen::Vector2d > &p2ds) override
 Virtual function to project a landmark in the image plane. More...
 
bool project (const Eigen::Affine3d &T_w_lmk, const std::shared_ptr< AModel3d > ldmk_model, const Eigen::Affine3d &T_f_w, std::vector< Eigen::Vector2d > &p2ds) override
 Virtual function to project a landmark in the image plane with the pose of the frame. More...
 
bool project (const Eigen::Affine3d &T_w_lmk, const Eigen::Affine3d &T_f_w, const Eigen::Matrix2d sqrt_info, Eigen::Vector2d &p2d, double *J_proj_frame, double *J_proj_lmk) override
 Virtual function to project a landmark and compute the Jacobian of the projection. More...
 
Eigen::Vector3d getRayCamera (Eigen::Vector2d f)
 Get the ray in camera coordinates. More...
 
Eigen::Vector3d getRay (Eigen::Vector2d f)
 Get the ray in world coordinates. More...
 
double getFocal () override
 Compute the focal length of the camera. More...
 
- Public Member Functions inherited from isae::ImageSensor
 ImageSensor ()
 
 ~ImageSensor ()
 
bool hasDepth ()
 
cv::Mat getRawData ()
 
void setPyr (const std::vector< cv::Mat > &img_pyr)
 
const std::vector< cv::Mat > getPyr ()
 
void applyCLAHE (float clahe_clip)
 Apply CLAHE (Contrast Limited Adaptive Histogram Equalization) to the image. More...
 
void histogramEqualization ()
 Apply histogram equalization to the image. More...
 
void imageNormalization ()
 Apply Image normalization to the image. More...
 
void applyAGCWD (float alpha)
 Apply adaptive gamme correction. More...
 
void setMask (cv::Mat mask)
 
cv::Mat getMask ()
 
Eigen::Matrix3d getCalibration ()
 
void addFeature (std::string feature_label, std::shared_ptr< AFeature > f)
 Add a single feature and compute its bearing vector. More...
 
void addFeatures (std::string feature_label, std::vector< std::shared_ptr< AFeature >> features)
 Add a vector of features and compute their bearing vectors. More...
 
void removeFeature (std::shared_ptr< AFeature > f)
 
typed_vec_featuresgetFeatures ()
 
void purgeFeatures (std::string feature_label)
 Clear all features of a specific type. More...
 
std::vector< std::shared_ptr< AFeature > > & getFeatures (std::string feature_label)
 Get features of a specific type. More...
 
- Public Member Functions inherited from isae::ASensor
 ASensor (std::string type)
 
 ~ASensor ()
 
std::string getType ()
 
void setFrame (std::shared_ptr< Frame > frame)
 
std::shared_ptr< FramegetFrame ()
 
void setFrame2SensorTransform (Eigen::Affine3d T_s_f)
 
Eigen::Affine3d getFrame2SensorTransform ()
 
Eigen::Affine3d getWorld2SensorTransform ()
 
Eigen::Affine3d getSensor2WorldTransform ()
 

Additional Inherited Members

- Protected Attributes inherited from isae::ImageSensor
Eigen::Matrix3d _calibration
 intrinsic matrix of the camera (sensor ?) More...
 
cv::Mat _raw_data
 Raw image data. More...
 
std::vector< cv::Mat > _img_pyr
 Image pyramid for multi-scale processing. More...
 
cv::Mat _mask
 Mask to ignore. More...
 
typed_vec_features _features
 Typed vector of features. More...
 
bool _has_depth
 Is it a RGBD ? More...
 
std::mutex _cam_mtx
 
- Protected Attributes inherited from isae::ASensor
std::weak_ptr< Frame_frame
 
Eigen::Affine3d _T_s_f
 
std::string _type
 
std::mutex _sensor_mtx
 

Detailed Description

An image sensor class that uses a double sphere model.

The implmementation of the double sphere model is based on the paper: "The Double Sphere Camera Model" by Usenko et al. Available at https://arxiv.org/abs/1807.08957

Constructor & Destructor Documentation

◆ DoubleSphere()

isae::DoubleSphere::DoubleSphere ( const cv::Mat &  image,
Eigen::Matrix3d  K,
double  alpha,
double  xi 
)
inline

Member Function Documentation

◆ getFocal()

double isae::DoubleSphere::getFocal ( )
inlineoverridevirtual

Compute the focal length of the camera.

Virtual function because it depends on the camera model.

Implements isae::ImageSensor.

◆ getRay()

Eigen::Vector3d isae::DoubleSphere::getRay ( Eigen::Vector2d  f)
virtual

Get the ray in world coordinates.

Implements isae::ImageSensor.

◆ getRayCamera()

Eigen::Vector3d isae::DoubleSphere::getRayCamera ( Eigen::Vector2d  f)
virtual

Get the ray in camera coordinates.

Implements isae::ImageSensor.

◆ project() [1/3]

bool isae::DoubleSphere::project ( const Eigen::Affine3d &  T_w_lmk,
const Eigen::Affine3d &  T_f_w,
const Eigen::Matrix2d  sqrt_info,
Eigen::Vector2d &  p2d,
double *  J_proj_frame,
double *  J_proj_lmk 
)
overridevirtual

Virtual function to project a landmark and compute the Jacobian of the projection.

Implements isae::ImageSensor.

◆ project() [2/3]

bool isae::DoubleSphere::project ( const Eigen::Affine3d &  T_w_lmk,
const std::shared_ptr< AModel3d ldmk_model,
const Eigen::Affine3d &  T_f_w,
std::vector< Eigen::Vector2d > &  p2d_vector 
)
overridevirtual

Virtual function to project a landmark in the image plane with the pose of the frame.

Implements isae::ImageSensor.

◆ project() [3/3]

bool isae::DoubleSphere::project ( const Eigen::Affine3d &  T_w_lmk,
const std::shared_ptr< AModel3d ldmk_model,
std::vector< Eigen::Vector2d > &  p2d_vector 
)
overridevirtual

Virtual function to project a landmark in the image plane.

Implements isae::ImageSensor.


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