20 #include "gtest/gtest.h" 26 constexpr
double kDuration = 3.f;
27 constexpr
double kGravityTimeConstant = 0.1 * kDuration;
28 constexpr
double kPrecision = 1e-8;
29 constexpr
int kSteps = 10;
31 class ImuTrackerTest :
public ::testing::Test {
33 void SetUp()
override {
39 Eigen::Quaterniond::Identity()),
44 for (
int i = 0; i < kSteps; ++i) {
46 imu_tracker_->AddImuAngularVelocityObservation(angular_velocity_);
59 TEST_F(ImuTrackerTest, IntegrateYawRotation) {
60 angular_velocity_ = Eigen::Vector3d(0, 0, 0.3);
62 Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
63 kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
65 imu_tracker_->orientation().angularDistance(expected_orientation),
69 TEST_F(ImuTrackerTest, IntegrateFullRotation) {
70 angular_velocity_ = Eigen::Vector3d(0.1, 0.4, 0.1);
75 Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
76 kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
78 imu_tracker_->orientation().angularDistance(expected_orientation),
82 TEST_F(ImuTrackerTest, LearnGravityVector) {
85 Eigen::Quaterniond expected_orientation;
87 Eigen::Vector3d::UnitZ());
89 imu_tracker_->orientation().angularDistance(expected_orientation),
UniversalTimeScaleClock::time_point Time
Time FromUniversal(const int64 ticks)
Duration FromSeconds(const double seconds)
Eigen::Vector3d linear_acceleration_
Eigen::Vector3d angular_velocity_
std::unique_ptr< ImuTracker > imu_tracker_