GLIM
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
glim::SubMappingBase Class Referenceabstract

Sub mapping base class. More...

#include <sub_mapping_base.hpp>

Inheritance diagram for glim::SubMappingBase:
Inheritance graph
[legend]

Public Member Functions

virtual void insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
 Insert an IMU data.
 
virtual void insert_frame (const EstimationFrame::ConstPtr &frame)
 Insert an odometry estimation frame.
 
virtual std::vector< SubMap::Ptr > get_submaps ()=0
 Get the created submaps.
 
virtual std::vector< SubMap::Ptr > submit_end_of_sequence ()
 Submit the signal to tell end of sequence and collect the remaining submap data.
 

Static Public Member Functions

static std::shared_ptr< SubMappingBaseload_module (const std::string &so_name)
 Load a sub mapping module from a shared library.
 

Protected Attributes

std::shared_ptr< spdlog::logger > logger
 

Detailed Description

Sub mapping base class.

Member Function Documentation

◆ get_submaps()

virtual std::vector< SubMap::Ptr > glim::SubMappingBase::get_submaps ( )
pure virtual

Get the created submaps.

Returns
Created submaps

Implemented in glim::SubMapping, and glim::SubMappingPassthrough.

◆ insert_frame()

virtual void glim::SubMappingBase::insert_frame ( const EstimationFrame::ConstPtr &  frame)
virtual

Insert an odometry estimation frame.

Parameters
odom_frameMarginalized odometry estimation frame

Reimplemented in glim::SubMapping, and glim::SubMappingPassthrough.

◆ insert_imu()

virtual void glim::SubMappingBase::insert_imu ( const double  stamp,
const Eigen::Vector3d &  linear_acc,
const Eigen::Vector3d &  angular_vel 
)
virtual

Insert an IMU data.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

Reimplemented in glim::SubMapping.

◆ load_module()

static std::shared_ptr< SubMappingBase > glim::SubMappingBase::load_module ( const std::string &  so_name)
static

Load a sub mapping module from a shared library.

Parameters
so_nameShared library name
Returns
Loaded sub mapping module

◆ submit_end_of_sequence()

virtual std::vector< SubMap::Ptr > glim::SubMappingBase::submit_end_of_sequence ( )
inlinevirtual

Submit the signal to tell end of sequence and collect the remaining submap data.

Returns
std::vector<SubMap::Ptr>

Reimplemented in glim::SubMapping, and glim::SubMappingPassthrough.


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