Odometry estimation executor to wrap and asynchronously run OdometryEstimationBase.
More...
#include <async_odometry_estimation.hpp>
|
| | AsyncOdometryEstimation (const std::shared_ptr< OdometryEstimationBase > &odometry_estimation, bool enable_imu) |
| | Construct a new Async Odometry Estimation object.
|
| |
|
| ~AsyncOdometryEstimation () |
| | Destroy the Async Odometry Estimation object.
|
| |
| void | insert_imu (const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) |
| | Insert an IMU data into the odometry estimation.
|
| |
| void | insert_frame (const PreprocessedFrame::Ptr &frame) |
| | Insert a preprocessed point cloud into odometry estimation.
|
| |
|
void | join () |
| | Wait for the odometry estimation thread.
|
| |
|
int | workload () const |
| | Get the size of the input queue.
|
| |
| void | get_results (std::vector< EstimationFrame::ConstPtr > &estimation_results, std::vector< EstimationFrame::ConstPtr > &marginalized_frames) |
| | Get the estimation results.
|
| |
Odometry estimation executor to wrap and asynchronously run OdometryEstimationBase.
- Note
- All the exposed public methods are thread-safe
◆ AsyncOdometryEstimation()
| glim::AsyncOdometryEstimation::AsyncOdometryEstimation |
( |
const std::shared_ptr< OdometryEstimationBase > & |
odometry_estimation, |
|
|
bool |
enable_imu |
|
) |
| |
Construct a new Async Odometry Estimation object.
- Parameters
-
| odometry_estimation | Odometry estimation to be wrapped |
◆ get_results()
| void glim::AsyncOdometryEstimation::get_results |
( |
std::vector< EstimationFrame::ConstPtr > & |
estimation_results, |
|
|
std::vector< EstimationFrame::ConstPtr > & |
marginalized_frames |
|
) |
| |
Get the estimation results.
- Parameters
-
| estimation_results | Estimation results |
| marginalized_frames | Marginalized frames |
◆ insert_frame()
| void glim::AsyncOdometryEstimation::insert_frame |
( |
const PreprocessedFrame::Ptr & |
frame | ) |
|
Insert a preprocessed point cloud into odometry estimation.
- Parameters
-
| frame | Preprocessed point cloud |
◆ insert_imu()
| void glim::AsyncOdometryEstimation::insert_imu |
( |
const double |
stamp, |
|
|
const Eigen::Vector3d & |
linear_acc, |
|
|
const Eigen::Vector3d & |
angular_vel |
|
) |
| |
Insert an IMU data into the odometry estimation.
- Parameters
-
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular velocity |
The documentation for this class was generated from the following file: