|
GLIM
|
LiDAR-only odometry estimation based on CT-GICP scan-to-model matching. More...
#include <odometry_estimation_ct.hpp>


Public Member Functions | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OdometryEstimationCT (const OdometryEstimationCTParams ¶ms=OdometryEstimationCTParams()) |
| virtual bool | requires_imu () const override |
| Returns true if the odometry estimation module requires IMU data. | |
| virtual EstimationFrame::ConstPtr | insert_frame (const PreprocessedFrame::Ptr &frame, std::vector< EstimationFrame::ConstPtr > &marginalized_frames) override |
| Insert a point cloud. | |
Public Member Functions inherited from glim::OdometryEstimationBase | |
| virtual void | insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) |
| Insert an IMU data. | |
| virtual std::vector< EstimationFrame::ConstPtr > | get_remaining_frames () |
| Pop out the remaining non-marginalized frames (called at the end of the sequence) | |
Additional Inherited Members | |
Static Public Member Functions inherited from glim::OdometryEstimationBase | |
| static std::shared_ptr< OdometryEstimationBase > | load_module (const std::string &so_name) |
| Load an odometry estimation module from a dynamic library. | |
Protected Attributes inherited from glim::OdometryEstimationBase | |
| std::shared_ptr< spdlog::logger > | logger |
LiDAR-only odometry estimation based on CT-GICP scan-to-model matching.
|
overridevirtual |
Insert a point cloud.
| frame | Preprocessed point cloud |
| marginalized_states | [out] Marginalized estimation frames |
Reimplemented from glim::OdometryEstimationBase.
|
inlineoverridevirtual |
Returns true if the odometry estimation module requires IMU data.
Reimplemented from glim::OdometryEstimationBase.