Utility class to integrate IMU measurements.
More...
#include <imu_integration.hpp>
|
|
| IMUIntegration (const IMUIntegrationParams ¶ms=IMUIntegrationParams()) |
| |
| void | insert_imu (double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) |
| | Insert an IMU data.
|
| |
| int | integrate_imu (double start_time, double end_time, const gtsam::imuBias::ConstantBias &bias, int *num_integrated) |
| | Integrate IMU measurements in a time range.
|
| |
| int | integrate_imu (double start_time, double end_time, const gtsam::NavState &state, const gtsam::imuBias::ConstantBias &bias, std::vector< double > &pred_times, std::vector< Eigen::Isometry3d > &pred_poses) |
| | Integrate IMU measurements and predict IMU poses in a time range.
|
| |
| int | find_imu_data (double start_time, double end_time, std::vector< double > &delta_times, std::vector< Eigen::Matrix< double, 7, 1 > > &imu_data) |
| | Find IMU data in a time range.
|
| |
| void | erase_imu_data (int last) |
| | Erase IMU data before the given index.
|
| |
|
const gtsam::PreintegratedImuMeasurements & | integrated_measurements () const |
| | Preintegrated measurements.
|
| |
|
const std::deque< Eigen::Matrix< double, 7, 1 > > & | imu_data_in_queue () const |
| | IMU data in queue.
|
| |
Utility class to integrate IMU measurements.
◆ erase_imu_data()
| void glim::IMUIntegration::erase_imu_data |
( |
int |
last | ) |
|
Erase IMU data before the given index.
- Parameters
-
| last | Last integrated IMU measurement index |
◆ find_imu_data()
| int glim::IMUIntegration::find_imu_data |
( |
double |
start_time, |
|
|
double |
end_time, |
|
|
std::vector< double > & |
delta_times, |
|
|
std::vector< Eigen::Matrix< double, 7, 1 > > & |
imu_data |
|
) |
| |
Find IMU data in a time range.
- Parameters
-
| start_time | Start time |
| end_time | End time |
| delta_times | Delta times (interval between IMU frames) |
| imu_data | IMU data |
- Returns
- Index of the last integrated IMU frame
◆ insert_imu()
| void glim::IMUIntegration::insert_imu |
( |
double |
stamp, |
|
|
const Eigen::Vector3d & |
linear_acc, |
|
|
const Eigen::Vector3d & |
angular_vel |
|
) |
| |
Insert an IMU data.
- Parameters
-
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular velocity |
◆ integrate_imu() [1/2]
| int glim::IMUIntegration::integrate_imu |
( |
double |
start_time, |
|
|
double |
end_time, |
|
|
const gtsam::imuBias::ConstantBias & |
bias, |
|
|
int * |
num_integrated |
|
) |
| |
Integrate IMU measurements in a time range.
- Parameters
-
| start_time | Integration starting time |
| end_time | Integration ending time |
| bias | IMU bias |
| num_integrated | Number of integrated IMU measurements |
- Returns
- Index of the last integrated IMU frame
◆ integrate_imu() [2/2]
| int glim::IMUIntegration::integrate_imu |
( |
double |
start_time, |
|
|
double |
end_time, |
|
|
const gtsam::NavState & |
state, |
|
|
const gtsam::imuBias::ConstantBias & |
bias, |
|
|
std::vector< double > & |
pred_times, |
|
|
std::vector< Eigen::Isometry3d > & |
pred_poses |
|
) |
| |
Integrate IMU measurements and predict IMU poses in a time range.
- Parameters
-
| start_time | Integration starting time |
| end_time | Integration ending time |
| state | IMU NavState |
| bias | IMU bias |
| pred_times | Timestamps of predicted IMU poses |
| pred_poses | Predicted IMU poses |
- Returns
- Index of the last integrated IMU frame
The documentation for this class was generated from the following file: