4#include <Eigen/Geometry>
7#include <opencv2/core.hpp>
9#include <glim/odometry/estimation_frame.hpp>
10#include <glim/preprocess/preprocessed_frame.hpp>
38 virtual void insert_image(
const double stamp,
const cv::Mat& image);
47 virtual void insert_imu(
const double stamp,
const Eigen::Vector3d& linear_acc,
const Eigen::Vector3d& angular_vel);
55 virtual EstimationFrame::ConstPtr
insert_frame(
const PreprocessedFrame::Ptr& frame, std::vector<EstimationFrame::ConstPtr>& marginalized_states);
61 virtual std::vector<EstimationFrame::ConstPtr>
get_remaining_frames() {
return std::vector<EstimationFrame::ConstPtr>(); }
68 static std::shared_ptr<OdometryEstimationBase>
load_module(
const std::string& so_name);
72 std::shared_ptr<spdlog::logger> logger;
Odometry estimation base class.
Definition odometry_estimation_base.hpp:22
virtual void insert_imu(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
Insert an IMU data.
static std::shared_ptr< OdometryEstimationBase > load_module(const std::string &so_name)
Load an odometry estimation module from a dynamic library.
virtual std::vector< EstimationFrame::ConstPtr > get_remaining_frames()
Pop out the remaining non-marginalized frames (called at the end of the sequence)
Definition odometry_estimation_base.hpp:61
virtual EstimationFrame::ConstPtr insert_frame(const PreprocessedFrame::Ptr &frame, std::vector< EstimationFrame::ConstPtr > &marginalized_states)
Insert a point cloud.
virtual bool requires_imu() const
Returns true if the odometry estimation module requires IMU data.
Definition odometry_estimation_base.hpp:30