GLIM
Loading...
Searching...
No Matches
Public Member Functions | List of all members
glim::IMUIntegration Class Reference

Utility class to integrate IMU measurements. More...

#include <imu_integration.hpp>

Public Member Functions

 IMUIntegration (const IMUIntegrationParams &params=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.
 

Detailed Description

Utility class to integrate IMU measurements.

Member Function Documentation

◆ erase_imu_data()

void glim::IMUIntegration::erase_imu_data ( int  last)

Erase IMU data before the given index.

Parameters
lastLast 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_timeStart time
end_timeEnd time
delta_timesDelta times (interval between IMU frames)
imu_dataIMU 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
stampTimestamp
linear_accLinear acceleration
angular_velAngular 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_timeIntegration starting time
end_timeIntegration ending time
biasIMU bias
num_integratedNumber 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_timeIntegration starting time
end_timeIntegration ending time
stateIMU NavState
biasIMU bias
pred_timesTimestamps of predicted IMU poses
pred_posesPredicted IMU poses
Returns
Index of the last integrated IMU frame

The documentation for this class was generated from the following file: