GLIM
Loading...
Searching...
No Matches
odometry_estimation_base.hpp
1#pragma once
2
3#include <Eigen/Core>
4#include <Eigen/Geometry>
5
6#ifdef GLIM_USE_OPENCV
7#include <opencv2/core.hpp>
8#endif
9#include <glim/odometry/estimation_frame.hpp>
10#include <glim/preprocess/preprocessed_frame.hpp>
11
12namespace spdlog {
13class logger;
14}
15
16namespace glim {
17
23public:
25 virtual ~OdometryEstimationBase() {}
26
30 virtual bool requires_imu() const { return true; }
31
32#ifdef GLIM_USE_OPENCV
38 virtual void insert_image(const double stamp, const cv::Mat& image);
39#endif
40
47 virtual void insert_imu(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel);
48
55 virtual EstimationFrame::ConstPtr insert_frame(const PreprocessedFrame::Ptr& frame, std::vector<EstimationFrame::ConstPtr>& marginalized_states);
56
61 virtual std::vector<EstimationFrame::ConstPtr> get_remaining_frames() { return std::vector<EstimationFrame::ConstPtr>(); }
62
68 static std::shared_ptr<OdometryEstimationBase> load_module(const std::string& so_name);
69
70protected:
71 // Logging
72 std::shared_ptr<spdlog::logger> logger;
73};
74
75} // namespace glim
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