SaDVIO
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
isae::LocalMap Class Reference

Class for a Local Map. More...

#include <localmap.h>

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

Public Member Functions

 LocalMap ()=default
 
 LocalMap (size_t min_kf_number, size_t max_kf_number, size_t fixedFrameNumber)
 
void addFrame (std::shared_ptr< Frame > &frame) override
 Add a frame to the local map. More...
 
void removeFrame (std::shared_ptr< Frame > &frame)
 Remove a frame from the local map. More...
 
size_t getWindowSize ()
 
size_t getFixedFrameNumber ()
 
std::vector< Eigen::Affine3d > & getOldFramesPoses ()
 
bool computeRelativePose (std::shared_ptr< Frame > &frame1, std::shared_ptr< Frame > &frame2, Eigen::Affine3d &T_f1_f2, Eigen::MatrixXd &cov)
 Compute the relative pose between two frames. More...
 
bool getMarginalizationFlag ()
 
void discardLastFrame ()
 Discard the last frame from the local map. More...
 
void reset ()
 Reset the local map. More...
 
- Public Member Functions inherited from isae::AMap
 AMap ()=default
 
virtual void addFrame (std::shared_ptr< isae::Frame > &frame)=0
 Add a frame to the map. More...
 
std::deque< std::shared_ptr< Frame > > & getFrames ()
 
std::shared_ptr< isae::FramegetLastFrame ()
 Get the last frame added to the map. More...
 
void getLastNFramesIn (size_t N, std::vector< std::shared_ptr< isae::Frame >> &dest)
 Provides the last N frames added to the map. More...
 
typed_vec_landmarksgetLandmarks ()
 
size_t getMapSize ()
 
void pushLandmarks (std::shared_ptr< isae::Frame > &frame)
 Add all the landmarks of a frame to the map. More...
 

Protected Member Functions

void removeEmptyLandmarks ()
 Remove landmarks from the local map that do not have any features. More...
 

Protected Attributes

size_t _min_kf_number = 1
 number of keyframes that are added by default when the map starts More...
 
size_t _max_kf_number = 7
 size of the sliding window More...
 
size_t _fixed_frames_number = 1
 number of frame that remain static during windowed BA More...
 
bool _margin_flag
 flag raised if the the last frame needs to be marginalized More...
 
std::vector< Eigen::Affine3d > _removed_frame_poses
 old frames poses, for debugging purposes More...
 
std::mutex _localmap_mtx
 
- Protected Attributes inherited from isae::AMap
std::deque< std::shared_ptr< Frame > > _frames
 A deque of frames in the map, ordered by time. More...
 
typed_vec_landmarks _landmarks
 All types of landmark in the map stored as std vectors. More...
 

Detailed Description

Class for a Local Map.

This is a local map that implements a sliding window approach.

Constructor & Destructor Documentation

◆ LocalMap() [1/2]

isae::LocalMap::LocalMap ( )
default

◆ LocalMap() [2/2]

isae::LocalMap::LocalMap ( size_t  min_kf_number,
size_t  max_kf_number,
size_t  fixedFrameNumber 
)

Member Function Documentation

◆ addFrame()

void isae::LocalMap::addFrame ( std::shared_ptr< Frame > &  frame)
override

Add a frame to the local map.

This method adds a frame to the local map and also pushes its landmarks into the map. It implements a sliding window approach, removing the oldest frame if the maximum number of keyframes is reached.

◆ computeRelativePose()

bool isae::LocalMap::computeRelativePose ( std::shared_ptr< Frame > &  frame1,
std::shared_ptr< Frame > &  frame2,
Eigen::Affine3d &  T_f1_f2,
Eigen::MatrixXd &  cov 
)

Compute the relative pose between two frames.

This method computes the relative pose between two frames of the local map and derives the covariance of the pose estimation.

◆ discardLastFrame()

void isae::LocalMap::discardLastFrame ( )

Discard the last frame from the local map.

This method discards the last frame from the local map and updates the sliding window accordingly. It also sets the marginalization flag to false.

◆ getFixedFrameNumber()

size_t isae::LocalMap::getFixedFrameNumber ( )
inline

◆ getMarginalizationFlag()

bool isae::LocalMap::getMarginalizationFlag ( )
inline

◆ getOldFramesPoses()

std::vector<Eigen::Affine3d>& isae::LocalMap::getOldFramesPoses ( )
inline

◆ getWindowSize()

size_t isae::LocalMap::getWindowSize ( )
inline

◆ removeEmptyLandmarks()

void isae::LocalMap::removeEmptyLandmarks ( )
protected

Remove landmarks from the local map that do not have any features.

This method iterates through all landmarks in the local map and removes those that have no associated features. It is called after discarding a frame to ensure the map remains clean.

◆ removeFrame()

void isae::LocalMap::removeFrame ( std::shared_ptr< Frame > &  frame)

Remove a frame from the local map.

This method removes a frame from the local map and also removes its landmarks from the map. It updates the sliding window accordingly.

◆ reset()

void isae::LocalMap::reset ( )

Reset the local map.

This method resets the local map, clearing all frames and landmarks. It is useful for reinitializing the local map in case of a failure or a new session.

Member Data Documentation

◆ _fixed_frames_number

size_t isae::LocalMap::_fixed_frames_number = 1
protected

number of frame that remain static during windowed BA

◆ _localmap_mtx

std::mutex isae::LocalMap::_localmap_mtx
mutableprotected

◆ _margin_flag

bool isae::LocalMap::_margin_flag
protected

flag raised if the the last frame needs to be marginalized

◆ _max_kf_number

size_t isae::LocalMap::_max_kf_number = 7
protected

size of the sliding window

◆ _min_kf_number

size_t isae::LocalMap::_min_kf_number = 1
protected

number of keyframes that are added by default when the map starts

◆ _removed_frame_poses

std::vector<Eigen::Affine3d> isae::LocalMap::_removed_frame_poses
protected

old frames poses, for debugging purposes


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