Sub mapping base class.
More...
#include <sub_mapping_base.hpp>
|
| 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 std::shared_ptr< SubMappingBase > | load_module (const std::string &so_name) |
| | Load a sub mapping module from a shared library.
|
| |
|
|
std::shared_ptr< spdlog::logger > | logger |
| |
◆ get_submaps()
| virtual std::vector< SubMap::Ptr > glim::SubMappingBase::get_submaps |
( |
| ) |
|
|
pure virtual |
◆ insert_frame()
| virtual void glim::SubMappingBase::insert_frame |
( |
const EstimationFrame::ConstPtr & |
frame | ) |
|
|
virtual |
◆ 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
-
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular 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_name | Shared library name |
- Returns
- Loaded sub mapping module
◆ submit_end_of_sequence()
| virtual std::vector< SubMap::Ptr > glim::SubMappingBase::submit_end_of_sequence |
( |
| ) |
|
|
inlinevirtual |
The documentation for this class was generated from the following file: