#include <algorithm>
#include <deque>
#include "Eigen/Core"
#include "Eigen/Geometry"
#include "cartographer/common/time.h"
#include "cartographer/sensor/imu_data.h"
#include "cartographer/transform/transform.h"
#include "glog/logging.h"
Go to the source code of this file.
|
template<typename T , typename RangeType , typename IteratorType > |
IntegrateImuResult< T > | cartographer::mapping::IntegrateImu (const RangeType &imu_data, const Eigen::Transform< T, 3, Eigen::Affine > &linear_acceleration_calibration, const Eigen::Transform< T, 3, Eigen::Affine > &angular_velocity_calibration, const common::Time start_time, const common::Time end_time, IteratorType *const it) |
|
template<typename RangeType , typename IteratorType > |
IntegrateImuResult< double > | cartographer::mapping::IntegrateImu (const RangeType &imu_data, const common::Time start_time, const common::Time end_time, IteratorType *const it) |
|