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

Odometry estimation base class. More...

#include <odometry_estimation_base.hpp>

Inheritance diagram for glim::OdometryEstimationBase:
Inheritance graph
[legend]

Public Member Functions

virtual bool requires_imu () const
 Returns true if the odometry estimation module requires IMU data.
 
virtual void insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
 Insert an IMU data.
 
virtual EstimationFrame::ConstPtr insert_frame (const PreprocessedFrame::Ptr &frame, std::vector< EstimationFrame::ConstPtr > &marginalized_states)
 Insert a point cloud.
 
virtual std::vector< EstimationFrame::ConstPtr > get_remaining_frames ()
 Pop out the remaining non-marginalized frames (called at the end of the sequence)
 

Static Public Member Functions

static std::shared_ptr< OdometryEstimationBaseload_module (const std::string &so_name)
 Load an odometry estimation module from a dynamic library.
 

Protected Attributes

std::shared_ptr< spdlog::logger > logger
 

Detailed Description

Odometry estimation base class.

Member Function Documentation

◆ get_remaining_frames()

virtual std::vector< EstimationFrame::ConstPtr > glim::OdometryEstimationBase::get_remaining_frames ( )
inlinevirtual

Pop out the remaining non-marginalized frames (called at the end of the sequence)

Returns
std::vector<EstimationFrame::ConstPtr>

Reimplemented in glim::OdometryEstimationIMU.

◆ insert_frame()

virtual EstimationFrame::ConstPtr glim::OdometryEstimationBase::insert_frame ( const PreprocessedFrame::Ptr &  frame,
std::vector< EstimationFrame::ConstPtr > &  marginalized_states 
)
virtual

Insert a point cloud.

Parameters
framePreprocessed point cloud
marginalized_states[out] Marginalized estimation frames
Returns
EstimationFrame::ConstPtr Estimation result for the latest frame

Reimplemented in glim::OdometryEstimationCT, and glim::OdometryEstimationIMU.

◆ insert_imu()

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

Insert an IMU data.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

Reimplemented in glim::OdometryEstimationIMU.

◆ load_module()

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

Load an odometry estimation module from a dynamic library.

Parameters
so_nameDynamic library name
Returns
Loaded odometry estimation module

◆ requires_imu()

virtual bool glim::OdometryEstimationBase::requires_imu ( ) const
inlinevirtual

Returns true if the odometry estimation module requires IMU data.

Reimplemented in glim::OdometryEstimationCT.


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