SaDVIO
|
Abstract class for initializing landmarks. More...
#include <alandmarkinitializer.h>
Public Member Functions | |
ALandmarkInitializer ()=default | |
~ALandmarkInitializer () | |
uint | initFromMatch (feature_pair match) |
Initialize landmarks from a feature pair. More... | |
uint | initFromMatches (vec_match matches) |
Initialize landmarks from a vector of feature matches. More... | |
uint | initFromFeatures (std::vector< std::shared_ptr< AFeature >> feats) |
Initialize landmarks from a vector of feature tracks. More... | |
Protected Member Functions | |
std::shared_ptr< ALandmark > | createNewLandmark (std::shared_ptr< AFeature > f1, std::shared_ptr< AFeature > f2) |
Create a new landmark from a pair of features. More... | |
virtual bool | initLandmark (std::vector< std::shared_ptr< AFeature >> features, std::shared_ptr< ALandmark > &landmark)=0 |
Initialize a landmark from a set of features. More... | |
virtual bool | initLandmarkWithDepth (std::vector< std::shared_ptr< AFeature >> features, std::shared_ptr< ALandmark > &landmark)=0 |
Initialize a landmark from a set of features with depth information. More... | |
virtual std::shared_ptr< ALandmark > | createNewLandmark (std::shared_ptr< AFeature > f)=0 |
Abstract class for initializing landmarks.
This class provides methods to initialize landmarks from feature matches or to update existing landmarks Each novel type of landmark must have its own derived class that implements the specific initialization logic.
|
default |
|
inline |
|
protectedpure virtual |
Implemented in isae::Line3DLandmarkInitializer.
|
protected |
Create a new landmark from a pair of features.
f1 | The first feature. |
f2 | The second feature. |
uint isae::ALandmarkInitializer::initFromFeatures | ( | std::vector< std::shared_ptr< AFeature >> | feats | ) |
Initialize landmarks from a vector of feature tracks.
tracks | The vector of feature tracks to initialize the landmarks from. |
uint isae::ALandmarkInitializer::initFromMatch | ( | feature_pair | match | ) |
Initialize landmarks from a feature pair.
match | The feature pair to initialize the landmark from. |
uint isae::ALandmarkInitializer::initFromMatches | ( | vec_match | matches | ) |
Initialize landmarks from a vector of feature matches.
matches | The vector of feature matches to initialize the landmarks from. |
|
protectedpure virtual |
Initialize a landmark from a set of features.
features | A vector of features. |
landmark | A shared pointer to the landmark to be initialized. |
Implemented in isae::Line3DLandmarkInitializer.
|
protectedpure virtual |
Initialize a landmark from a set of features with depth information.
features | A vector of features. |
landmark | A shared pointer to the landmark to be initialized. |
Implemented in isae::Line3DLandmarkInitializer.