Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ov_msckf::UpdaterSLAM Class Reference

Will compute the system for our sparse SLAM features and update the filter. More...

#include <UpdaterSLAM.h>

Public Member Functions

void change_anchors (std::shared_ptr< State > state)
 Will change SLAM feature anchors if it will be marginalized. More...
 
void delayed_init (std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
 Given max track features, this will try to use them to initialize them in the state. More...
 
void update (std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
 Given tracked SLAM features, this will try to use them to update the state. More...
 
 UpdaterSLAM (UpdaterOptions &options_slam, UpdaterOptions &options_aruco, ov_core::FeatureInitializerOptions &feat_init_options)
 Default constructor for our SLAM updater. More...
 

Protected Member Functions

void perform_anchor_change (std::shared_ptr< State > state, std::shared_ptr< ov_type::Landmark > landmark, double new_anchor_timestamp, size_t new_cam_id)
 Shifts landmark anchor to new clone. More...
 

Protected Attributes

UpdaterOptions _options_aruco
 Options used during update for aruco features. More...
 
UpdaterOptions _options_slam
 Options used during update for slam features. More...
 
std::map< int, double > chi_squared_table
 Chi squared 95th percentile table (lookup would be size of residual) More...
 
std::shared_ptr< ov_core::FeatureInitializerinitializer_feat
 Feature initializer class object. More...
 

Detailed Description

Will compute the system for our sparse SLAM features and update the filter.

This class is responsible for performing delayed feature initialization, SLAM update, and SLAM anchor change for anchored feature representations.

Definition at line 50 of file UpdaterSLAM.h.

Constructor & Destructor Documentation

◆ UpdaterSLAM()

UpdaterSLAM::UpdaterSLAM ( UpdaterOptions options_slam,
UpdaterOptions options_aruco,
ov_core::FeatureInitializerOptions feat_init_options 
)

Default constructor for our SLAM updater.

Our updater has a feature initializer which we use to initialize features as needed. Also the options allow for one to tune the different parameters for update.

Parameters
options_slamUpdater options (include measurement noise value) for SLAM features
options_arucoUpdater options (include measurement noise value) for ARUCO features
feat_init_optionsFeature initializer options

Definition at line 43 of file UpdaterSLAM.cpp.

Member Function Documentation

◆ change_anchors()

void UpdaterSLAM::change_anchors ( std::shared_ptr< State state)

Will change SLAM feature anchors if it will be marginalized.

Makes sure that if any clone is about to be marginalized, it changes anchor representation. By default, this will shift the anchor into the newest IMU clone and keep the camera calibration anchor the same.

Parameters
stateState of the filter

Definition at line 481 of file UpdaterSLAM.cpp.

◆ delayed_init()

void UpdaterSLAM::delayed_init ( std::shared_ptr< State state,
std::vector< std::shared_ptr< ov_core::Feature >> &  feature_vec 
)

Given max track features, this will try to use them to initialize them in the state.

Parameters
stateState of the filter
feature_vecFeatures that can be used for update

Definition at line 61 of file UpdaterSLAM.cpp.

◆ perform_anchor_change()

void UpdaterSLAM::perform_anchor_change ( std::shared_ptr< State state,
std::shared_ptr< ov_type::Landmark landmark,
double  new_anchor_timestamp,
size_t  new_cam_id 
)
protected

Shifts landmark anchor to new clone.

Parameters
stateState of filter
landmarklandmark whose anchor is being shifter
new_anchor_timestampClone timestamp we want to move to
new_cam_idWhich camera frame we want to move to

Definition at line 505 of file UpdaterSLAM.cpp.

◆ update()

void UpdaterSLAM::update ( std::shared_ptr< State state,
std::vector< std::shared_ptr< ov_core::Feature >> &  feature_vec 
)

Given tracked SLAM features, this will try to use them to update the state.

Parameters
stateState of the filter
feature_vecFeatures that can be used for update

Definition at line 253 of file UpdaterSLAM.cpp.

Member Data Documentation

◆ _options_aruco

UpdaterOptions ov_msckf::UpdaterSLAM::_options_aruco
protected

Options used during update for aruco features.

Definition at line 104 of file UpdaterSLAM.h.

◆ _options_slam

UpdaterOptions ov_msckf::UpdaterSLAM::_options_slam
protected

Options used during update for slam features.

Definition at line 101 of file UpdaterSLAM.h.

◆ chi_squared_table

std::map<int, double> ov_msckf::UpdaterSLAM::chi_squared_table
protected

Chi squared 95th percentile table (lookup would be size of residual)

Definition at line 110 of file UpdaterSLAM.h.

◆ initializer_feat

std::shared_ptr<ov_core::FeatureInitializer> ov_msckf::UpdaterSLAM::initializer_feat
protected

Feature initializer class object.

Definition at line 107 of file UpdaterSLAM.h.


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


ov_msckf
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54