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

Global mapping with the old conventional pose graph optimization. More...

#include <global_mapping_pose_graph.hpp>

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

Public Member Functions

 GlobalMappingPoseGraph (const GlobalMappingPoseGraphParams &params=GlobalMappingPoseGraphParams())
 
virtual void insert_submap (const SubMap::Ptr &submap) override
 Insert a SubMap.
 
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.
 
- Public Member Functions inherited from glim::GlobalMappingBase
virtual void insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
 Insert an IMU frame.
 
virtual void find_overlapping_submaps (double min_overlap)
 Request to find new overlapping submaps.
 
virtual void recover_graph ()
 Request to detect and recover graph corruption.
 

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 with the old conventional pose graph optimization.

Note
We recommend using GlobalMapping instead of this class if accuracy matters.

Member Function Documentation

◆ export_points()

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

Export all the submap points.

Reimplemented from glim::GlobalMappingBase.

◆ insert_submap()

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

Insert a SubMap.

Parameters
submapSubMap

Reimplemented from glim::GlobalMappingBase.

◆ optimize()

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

Request to perform optimization.

Reimplemented from glim::GlobalMappingBase.

◆ save()

virtual void glim::GlobalMappingPoseGraph::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: