imu_tracker_test.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2017 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
20 #include "gtest/gtest.h"
21 
22 namespace cartographer {
23 namespace mapping {
24 namespace {
25 
26 constexpr double kDuration = 3.f;
27 constexpr double kGravityTimeConstant = 0.1 * kDuration;
28 constexpr double kPrecision = 1e-8;
29 constexpr int kSteps = 10;
30 
31 class ImuTrackerTest : public ::testing::Test {
32  protected:
33  void SetUp() override {
34  imu_tracker_ = common::make_unique<ImuTracker>(kGravityTimeConstant, time_);
35  angular_velocity_ = Eigen::Vector3d(0, 0, 0);
36  linear_acceleration_ = Eigen::Vector3d(0, 0, 9.9);
37  EXPECT_NEAR(0.,
38  imu_tracker_->orientation().angularDistance(
39  Eigen::Quaterniond::Identity()),
40  kPrecision);
41  }
42 
43  void AdvanceImu() {
44  for (int i = 0; i < kSteps; ++i) {
45  imu_tracker_->AddImuLinearAccelerationObservation(linear_acceleration_);
46  imu_tracker_->AddImuAngularVelocityObservation(angular_velocity_);
47  time_ += common::FromSeconds(kDuration / kSteps);
48  imu_tracker_->Advance(time_);
49  }
50  EXPECT_EQ(time_, imu_tracker_->time());
51  }
52 
53  Eigen::Vector3d angular_velocity_;
54  std::unique_ptr<ImuTracker> imu_tracker_;
55  Eigen::Vector3d linear_acceleration_;
57 };
58 
59 TEST_F(ImuTrackerTest, IntegrateYawRotation) {
60  angular_velocity_ = Eigen::Vector3d(0, 0, 0.3);
61  AdvanceImu();
62  Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
63  kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
64  EXPECT_NEAR(0.,
65  imu_tracker_->orientation().angularDistance(expected_orientation),
66  kPrecision);
67 }
68 
69 TEST_F(ImuTrackerTest, IntegrateFullRotation) {
70  angular_velocity_ = Eigen::Vector3d(0.1, 0.4, 0.1);
71  // Using a huge gravity time constant effectively disables gravity vector
72  // tracking.
73  imu_tracker_.reset(new ImuTracker(1e10 * kDuration, time_));
74  AdvanceImu();
75  Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
76  kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
77  EXPECT_NEAR(0.,
78  imu_tracker_->orientation().angularDistance(expected_orientation),
79  kPrecision);
80 }
81 
82 TEST_F(ImuTrackerTest, LearnGravityVector) {
83  linear_acceleration_ = Eigen::Vector3d(0.5, 0.3, 9.5);
84  AdvanceImu();
85  Eigen::Quaterniond expected_orientation;
86  expected_orientation.setFromTwoVectors(linear_acceleration_,
87  Eigen::Vector3d::UnitZ());
88  EXPECT_NEAR(0.,
89  imu_tracker_->orientation().angularDistance(expected_orientation),
90  kPrecision);
91 }
92 
93 } // namespace
94 } // namespace mapping
95 } // namespace cartographer
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
Duration FromSeconds(const double seconds)
Definition: time.cc:24
Eigen::Vector3d linear_acceleration_
common::Time time_
Eigen::Vector3d angular_velocity_
std::unique_ptr< ImuTracker > imu_tracker_


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58