Odometry estimation base class.
More...
#include <odometry_estimation_base.hpp>
|
| 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)
|
| |
|
|
std::shared_ptr< spdlog::logger > | logger |
| |
Odometry estimation base class.
◆ 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
-
| frame | Preprocessed 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
-
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular 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_name | Dynamic library name |
- Returns
- Loaded odometry estimation module
◆ requires_imu()
| virtual bool glim::OdometryEstimationBase::requires_imu |
( |
| ) |
const |
|
inlinevirtual |
The documentation for this class was generated from the following file: