|
|
| LooseInitialStateEstimation (const Eigen::Isometry3d &T_lidar_imu, const Eigen::Matrix< double, 6, 1 > &imu_bias) |
| |
| virtual void | insert_frame (const PreprocessedFrame::ConstPtr &raw_frame) override |
| | Insert a point cloud.
|
| |
| virtual void | insert_imu (double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) override |
| | Insert an IMU data.
|
| |
| virtual EstimationFrame::ConstPtr | initial_pose () override |
| | Get the initial estimation result.
|
| |
|
|
std::shared_ptr< spdlog::logger > | logger |
| |
◆ initial_pose()
| virtual EstimationFrame::ConstPtr glim::LooseInitialStateEstimation::initial_pose |
( |
| ) |
|
|
overridevirtual |
Get the initial estimation result.
- Returns
- EstimationFrame::ConstPtr Estimated initial state
-
nullptr If it's not ready
Implements glim::InitialStateEstimation.
◆ insert_frame()
| virtual void glim::LooseInitialStateEstimation::insert_frame |
( |
const PreprocessedFrame::ConstPtr & |
raw_frame | ) |
|
|
overridevirtual |
◆ insert_imu()
| virtual void glim::LooseInitialStateEstimation::insert_imu |
( |
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::InitialStateEstimation.
The documentation for this class was generated from the following file: