GLIM
Loading...
Searching...
No Matches
Public Member Functions | List of all members
glim::GlobalMapping Class Reference

Global mapping. More...

#include <global_mapping.hpp>

Inheritance diagram for glim::GlobalMapping:
Inheritance graph
[legend]
Collaboration diagram for glim::GlobalMapping:
Collaboration graph
[legend]

Public Member Functions

 GlobalMapping (const GlobalMappingParams &params=GlobalMappingParams())
 
virtual void insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) override
 Insert an IMU frame.
 
virtual void insert_submap (const SubMap::Ptr &submap) override
 Insert a SubMap.
 
virtual void find_overlapping_submaps (double min_overlap) override
 Request to find new overlapping submaps.
 
virtual void optimize () override
 Request to perform optimization.
 
virtual void save (const std::string &path) override
 Save the mapping result.
 
virtual gtsam_points::PointCloud::Ptr export_points () override
 Export all the submap points.
 
bool load (const std::string &path)
 Load a mapping result from a dumped directory.
 

Additional Inherited Members

- Static Public Member Functions inherited from glim::GlobalMappingBase
static std::shared_ptr< GlobalMappingBaseload_module (const std::string &so_name)
 Load a global mapping module from a shared library.
 
- Protected Attributes inherited from glim::GlobalMappingBase
std::shared_ptr< spdlog::logger > logger
 

Detailed Description

Global mapping.

Member Function Documentation

◆ export_points()

virtual gtsam_points::PointCloud::Ptr glim::GlobalMapping::export_points ( )
overridevirtual

Export all the submap points.

Reimplemented from glim::GlobalMappingBase.

◆ find_overlapping_submaps()

virtual void glim::GlobalMapping::find_overlapping_submaps ( double  min_overlap)
overridevirtual

Request to find new overlapping submaps.

Reimplemented from glim::GlobalMappingBase.

◆ insert_imu()

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

Insert an IMU frame.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

Reimplemented from glim::GlobalMappingBase.

◆ insert_submap()

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

Insert a SubMap.

Parameters
submapSubMap

Reimplemented from glim::GlobalMappingBase.

◆ load()

bool glim::GlobalMapping::load ( const std::string &  path)

Load a mapping result from a dumped directory.

Parameters
pathInput dump path

◆ optimize()

virtual void glim::GlobalMapping::optimize ( )
overridevirtual

Request to perform optimization.

Reimplemented from glim::GlobalMappingBase.

◆ save()

virtual void glim::GlobalMapping::save ( const std::string &  path)
overridevirtual

Save the mapping result.

Parameters
pathSave path

Reimplemented from glim::GlobalMappingBase.


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