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

A 3D bounding box landmark class. More...

#include <BBox3d.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW BBox3D ()
 
 BBox3D (std::vector< Eigen::Vector3d > T_w_l_vector, cv::Mat desc=cv::Mat())
 
 BBox3D (Eigen::Affine3d T_w_l, std::vector< std::shared_ptr< isae::AFeature >> features)
 
- Public Member Functions inherited from isae::ALandmark
 ALandmark ()
 
 ALandmark (Eigen::Affine3d T_w_l, std::vector< std::shared_ptr< isae::AFeature >> features)
 
 ~ALandmark ()
 
virtual void init (Eigen::Affine3d T_w_l, std::vector< std::shared_ptr< isae::AFeature >> features)
 Virtual Function to properly initialize a landmark. More...
 
void addFeature (std::shared_ptr< AFeature > feature)
 
std::vector< std::weak_ptr< AFeature > > getFeatures ()
 
void removeExpiredFeatures ()
 Remove features that are not linked to anything. More...
 
void removeFeature (std::shared_ptr< AFeature > f)
 
bool fuseWithLandmark (std::shared_ptr< ALandmark > landmark)
 Fuse this landmark with another one, the feature sets are merged. More...
 
void setPose (Eigen::Affine3d T_w_l)
 
void setPosition (Eigen::Vector3d t_w_l)
 Set only the translation of the landmark pose. More...
 
Eigen::Affine3d getPose () const
 
std::vector< Eigen::Vector3d > getModelPoints ()
 
std::shared_ptr< AModel3dgetModel () const
 
cv::Mat getDescriptor () const
 
void setDescriptor (cv::Mat descriptor)
 
bool isInitialized () const
 
void setUninitialized ()
 
void setInMap ()
 
bool isInMap ()
 
bool sanityCheck ()
 Check if the landmark is valid in terms of reprojection error and number of features. More...
 
virtual double chi2err (std::shared_ptr< AFeature > f)
 Compute the chi2 error for a given feature. More...
 
double avgChi2err ()
 Compute the average chi2 error for all features associated to the landmark. More...
 
bool isOutlier () const
 
void setOutlier ()
 
void setInlier ()
 
bool isResurected () const
 
void setResurected ()
 
bool hasPrior () const
 
void setPrior ()
 
bool isMarg () const
 
void setMarg ()
 

Additional Inherited Members

- Public Attributes inherited from isae::ALandmark
int _id
 Unique id for the landmark, used for bookeeping. More...
 
std::string _label
 Label for the landmark. More...
 
- Static Public Attributes inherited from isae::ALandmark
static int _landmark_count = 0
 Static counter for landmarks, used for unique id generation. More...
 
- Protected Attributes inherited from isae::ALandmark
bool _initialized = false
 Flag to check if the landmark is initialized. More...
 
bool _in_map = false
 Flag to check if the landmark is in the map. More...
 
bool _outlier = false
 Flag to check if the landmark is an outlier. More...
 
bool _is_resurected = false
 Flag to check if the landmark has been resurected. More...
 
bool _has_prior = false
 Flag to check if the landmark has a prior. More...
 
bool _is_marg = false
 Flag to check if the landmark is marginalised. More...
 
Eigen::Affine3d _T_w_l
 Landmark pose in world frame. More...
 
cv::Mat _descriptor
 Descriptor of the landmark, used for matching. More...
 
std::shared_ptr< AModel3d_model
 3D model of the landmark More...
 
std::vector< std::weak_ptr< AFeature > > _features
 Features associated to the landmark. More...
 
std::mutex _lmk_mtx
 

Detailed Description

A 3D bounding box landmark class.

BBox3D class represents a 3D boudning box in space, labeled as "bboxxd"..

Constructor & Destructor Documentation

◆ BBox3D() [1/3]

EIGEN_MAKE_ALIGNED_OPERATOR_NEW isae::BBox3D::BBox3D ( )
inline

◆ BBox3D() [2/3]

isae::BBox3D::BBox3D ( std::vector< Eigen::Vector3d >  T_w_l_vector,
cv::Mat  desc = cv::Mat() 
)
inline

◆ BBox3D() [3/3]

isae::BBox3D::BBox3D ( Eigen::Affine3d  T_w_l,
std::vector< std::shared_ptr< isae::AFeature >>  features 
)
inline

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