Base class for LiDAR-IMU odometry estimation.
More...
#include <odometry_estimation_imu.hpp>
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OdometryEstimationIMU (std::unique_ptr< OdometryEstimationIMUParams > &¶ms) |
| |
| virtual void | insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) override |
| | Insert an IMU data.
|
| |
| virtual EstimationFrame::ConstPtr | insert_frame (const PreprocessedFrame::Ptr &frame, std::vector< EstimationFrame::ConstPtr > &marginalized_frames) override |
| | Insert a point cloud.
|
| |
| virtual std::vector< EstimationFrame::ConstPtr > | get_remaining_frames () override |
| | Pop out the remaining non-marginalized frames (called at the end of the sequence)
|
| |
| virtual bool | requires_imu () const |
| | Returns true if the odometry estimation module requires IMU data.
|
| |
|
|
virtual void | create_frame (EstimationFrame::Ptr &frame) |
| |
|
virtual gtsam::NonlinearFactorGraph | create_factors (const int current, const gtsam_points::shared_ptr< gtsam::ImuFactor > &imu_factor, gtsam::Values &new_values)=0 |
| |
|
virtual void | fallback_smoother () |
| |
|
virtual void | update_frames (const int current, const gtsam::NonlinearFactorGraph &new_factors) |
| |
|
virtual void | update_smoother (const gtsam::NonlinearFactorGraph &new_factors, const gtsam::Values &new_values, const std::map< std::uint64_t, double > &new_stamp, int update_count=0) |
| |
|
virtual void | update_smoother (int update_count=1) |
| |
Base class for LiDAR-IMU odometry estimation.
◆ get_remaining_frames()
| virtual std::vector< EstimationFrame::ConstPtr > glim::OdometryEstimationIMU::get_remaining_frames |
( |
| ) |
|
|
overridevirtual |
Pop out the remaining non-marginalized frames (called at the end of the sequence)
- Returns
- std::vector<EstimationFrame::ConstPtr>
Reimplemented from glim::OdometryEstimationBase.
◆ insert_frame()
| virtual EstimationFrame::ConstPtr glim::OdometryEstimationIMU::insert_frame |
( |
const PreprocessedFrame::Ptr & |
frame, |
|
|
std::vector< EstimationFrame::ConstPtr > & |
marginalized_states |
|
) |
| |
|
overridevirtual |
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 from glim::OdometryEstimationBase.
◆ insert_imu()
| virtual void glim::OdometryEstimationIMU::insert_imu |
( |
const double |
stamp, |
|
|
const Eigen::Vector3d & |
linear_acc, |
|
|
const Eigen::Vector3d & |
angular_vel |
|
) |
| |
|
overridevirtual |
Insert an IMU data.
- Parameters
-
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular velocity |
Reimplemented from glim::OdometryEstimationBase.
The documentation for this class was generated from the following file: