23 #include "glog/logging.h" 29 double imu_gravity_time_constant)
30 : pose_queue_duration_(pose_queue_duration),
31 gravity_time_constant_(imu_gravity_time_constant),
32 cached_extrapolated_pose_{common::Time::min(),
37 const double imu_gravity_time_constant,
const sensor::ImuData& imu_data) {
38 auto extrapolator = common::make_unique<PoseExtrapolator>(
39 pose_queue_duration, imu_gravity_time_constant);
40 extrapolator->AddImuData(imu_data);
41 extrapolator->imu_tracker_ =
42 common::make_unique<ImuTracker>(imu_gravity_time_constant, imu_data.
time);
43 extrapolator->imu_tracker_->AddImuLinearAccelerationObservation(
45 extrapolator->imu_tracker_->AddImuAngularVelocityObservation(
47 extrapolator->imu_tracker_->Advance(imu_data.
time);
48 extrapolator->AddPose(
56 return common::Time::min();
63 return common::Time::min();
73 tracker_start = std::min(tracker_start,
imu_data_.front().time);
111 const double odometry_time_delta =
122 const Eigen::Vector3d
123 linear_velocity_in_tracking_frame_at_newest_odometry_time =
124 odometry_pose_delta.
translation() / odometry_time_delta;
125 const Eigen::Quaterniond orientation_at_newest_odometry_time =
130 orientation_at_newest_odometry_time *
131 linear_velocity_in_tracking_frame_at_newest_odometry_time;
136 CHECK_GE(time, newest_timed_pose.
time);
138 const Eigen::Vector3d translation =
140 const Eigen::Quaterniond rotation =
163 const auto newest_time = newest_timed_pose.time;
165 const auto oldest_time = oldest_timed_pose.
time;
167 if (queue_delta < 0.001) {
168 LOG(WARNING) <<
"Queue too short for velocity estimation. Queue duration: " 169 << queue_delta <<
" ms";
198 CHECK_GE(time, imu_tracker->
time());
213 auto it = std::lower_bound(
219 imu_tracker->
Advance(it->time);
229 CHECK_GE(time, imu_tracker->
time());
231 const Eigen::Quaterniond last_orientation =
imu_tracker_->orientation();
232 return last_orientation.inverse() * imu_tracker->
orientation();
237 const double extrapolation_delta =
UniversalTimeScaleClock::time_point Time
void AddImuLinearAccelerationObservation(const Eigen::Vector3d &imu_linear_acceleration)
common::Time time() const
UniversalTimeScaleClock::duration Duration
Eigen::Quaterniond orientation() const
void AddImuAngularVelocityObservation(const Eigen::Vector3d &imu_angular_velocity)
double ToSeconds(const Duration duration)
void Advance(common::Time time)
Eigen::Vector3d angular_velocity
Eigen::Vector3d linear_acceleration