GLIM
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
glim::SubMap Struct Reference

SubMap. More...

#include <sub_map.hpp>

Public Types

using Ptr = std::shared_ptr< SubMap >
 
using ConstPtr = std::shared_ptr< const SubMap >
 

Public Member Functions

void drop_frame_points ()
 Remove point clouds of the odometry estimation frames (to save memory)
 
EstimationFrame::ConstPtr origin_frame () const
 Get the origin frame.
 
EstimationFrame::ConstPtr origin_odom_frame () const
 Get the origin odometry frame.
 
template<typename T >
T * get_custom_data (const std::string &key)
 Get the custom data and cast it to the specified type.
 
template<typename T >
const T * get_custom_data (const std::string &key) const
 Get the custom data and cast it to the specified type.
 
void save (const std::string &path) const
 Save the submap.
 

Static Public Member Functions

static SubMap::Ptr load (const std::string &path)
 Load a submap from storage.
 

Public Attributes

int id
 submap ID
 
int session_id
 session ID (Used for only offline mapping)
 
Eigen::Isometry3d T_world_origin
 frame[frame.size() / 2] pose w.r.t. the world
 
Eigen::Isometry3d T_origin_endpoint_L
 frame.front() pose w.r.t. the origin
 
Eigen::Isometry3d T_origin_endpoint_R
 frame.back() pose w.r.t. the origin
 
gtsam_points::PointCloud::Ptr frame
 Merged submap frame.
 
std::vector< gtsam_points::GaussianVoxelMap::Ptr > voxelmaps
 Multi-resolution voxelmaps.
 
std::vector< EstimationFrame::ConstPtr > frames
 Optimized odometry frames.
 
std::vector< EstimationFrame::ConstPtr > odom_frames
 Original odometry frames.
 
std::unordered_map< std::string, std::shared_ptr< void > > custom_data
 User-defined custom data.
 

Detailed Description

SubMap.

Member Function Documentation

◆ get_custom_data() [1/2]

template<typename T >
T * glim::SubMap::get_custom_data ( const std::string &  key)
inline

Get the custom data and cast it to the specified type.

Note
This method does not check the type of the custom data.
Parameters
keyKey of the custom data
Returns
T* Pointer to the custom data. nullptr if not found.

◆ get_custom_data() [2/2]

template<typename T >
const T * glim::SubMap::get_custom_data ( const std::string &  key) const
inline

Get the custom data and cast it to the specified type.

Note
This method does not check the type of the custom data.
Parameters
keyKey of the custom data
Returns
T* Pointer to the custom data. nullptr if not found.

◆ load()

static SubMap::Ptr glim::SubMap::load ( const std::string &  path)
static

Load a submap from storage.

Parameters
pathLoad path
Returns
SubMap::Ptr Loaded SubMap
nullptr if failed to load

◆ save()

void glim::SubMap::save ( const std::string &  path) const

Save the submap.

Parameters
pathSave path

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