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

Global mapping base class. More...

#include <global_mapping_base.hpp>

Inheritance diagram for glim::GlobalMappingBase:
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 frame.
 
virtual void insert_submap (const SubMap::Ptr &submap)
 Insert a SubMap.
 
virtual void find_overlapping_submaps (double min_overlap)
 Request to find new overlapping submaps.
 
virtual void optimize ()
 Request to perform optimization.
 
virtual void recover_graph ()
 Request to detect and recover graph corruption.
 
virtual void save (const std::string &path)
 Save the mapping result.
 
virtual gtsam_points::PointCloud::Ptr export_points ()
 Export all the submap points.
 

Static Public Member Functions

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

Protected Attributes

std::shared_ptr< spdlog::logger > logger
 

Detailed Description

Global mapping base class.

Member Function Documentation

◆ export_points()

virtual gtsam_points::PointCloud::Ptr glim::GlobalMappingBase::export_points ( )
inlinevirtual

Export all the submap points.

Reimplemented in glim::GlobalMapping, and glim::GlobalMappingPoseGraph.

◆ find_overlapping_submaps()

virtual void glim::GlobalMappingBase::find_overlapping_submaps ( double  min_overlap)
virtual

Request to find new overlapping submaps.

Reimplemented in glim::GlobalMapping.

◆ insert_imu()

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

Insert an IMU frame.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

Reimplemented in glim::GlobalMapping.

◆ insert_submap()

virtual void glim::GlobalMappingBase::insert_submap ( const SubMap::Ptr &  submap)
virtual

Insert a SubMap.

Parameters
submapSubMap

Reimplemented in glim::GlobalMapping, and glim::GlobalMappingPoseGraph.

◆ load_module()

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

Load a global mapping module from a shared library.

Parameters
so_nameShared library name
Returns
Loaded global mapping module

◆ optimize()

virtual void glim::GlobalMappingBase::optimize ( )
virtual

Request to perform optimization.

Reimplemented in glim::GlobalMapping, and glim::GlobalMappingPoseGraph.

◆ save()

virtual void glim::GlobalMappingBase::save ( const std::string &  path)
inlinevirtual

Save the mapping result.

Parameters
pathSave path

Reimplemented in glim::GlobalMapping, and glim::GlobalMappingPoseGraph.


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