24 #include "glog/logging.h" 31 : imu_gravity_time_constant_(imu_gravity_time_constant),
33 last_linear_acceleration_time_(common::
Time::min()),
34 orientation_(
Eigen::Quaterniond::Identity()),
35 gravity_vector_(
Eigen::Vector3d::UnitZ()),
36 imu_angular_velocity_(
Eigen::Vector3d::Zero()) {}
39 CHECK_LE(
time_, time);
41 const Eigen::Quaterniond rotation =
50 const Eigen::Vector3d& imu_linear_acceleration) {
53 const double delta_t =
56 : std::numeric_limits<double>::infinity();
63 const Eigen::Quaterniond rotation = Eigen::Quaterniond::FromTwoVectors(
67 CHECK_GT((orientation_ * gravity_vector_).normalized().z(), 0.99);
71 const Eigen::Vector3d& imu_angular_velocity) {
Eigen::Vector3d imu_angular_velocity_
const double imu_gravity_time_constant_
UniversalTimeScaleClock::time_point Time
common::Time last_linear_acceleration_time_
ImuTracker(double imu_gravity_time_constant, common::Time time)
void AddImuLinearAccelerationObservation(const Eigen::Vector3d &imu_linear_acceleration)
Eigen::Vector3d gravity_vector_
void AddImuAngularVelocityObservation(const Eigen::Vector3d &imu_angular_velocity)
double ToSeconds(const Duration duration)
Eigen::Quaterniond orientation_
void Advance(common::Time time)