Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/imu_tracker.h"
00018
00019 #include "absl/memory/memory.h"
00020 #include "gtest/gtest.h"
00021
00022 namespace cartographer {
00023 namespace mapping {
00024 namespace {
00025
00026 constexpr double kDuration = 3.f;
00027 constexpr double kGravityTimeConstant = 0.1 * kDuration;
00028 constexpr double kPrecision = 1e-8;
00029 constexpr int kSteps = 10;
00030
00031 class ImuTrackerTest : public ::testing::Test {
00032 protected:
00033 void SetUp() override {
00034 imu_tracker_ = absl::make_unique<ImuTracker>(kGravityTimeConstant, time_);
00035 angular_velocity_ = Eigen::Vector3d(0, 0, 0);
00036 linear_acceleration_ = Eigen::Vector3d(0, 0, 9.9);
00037 EXPECT_NEAR(0.,
00038 imu_tracker_->orientation().angularDistance(
00039 Eigen::Quaterniond::Identity()),
00040 kPrecision);
00041 }
00042
00043 void AdvanceImu() {
00044 for (int i = 0; i < kSteps; ++i) {
00045 imu_tracker_->AddImuLinearAccelerationObservation(linear_acceleration_);
00046 imu_tracker_->AddImuAngularVelocityObservation(angular_velocity_);
00047 time_ += common::FromSeconds(kDuration / kSteps);
00048 imu_tracker_->Advance(time_);
00049 }
00050 EXPECT_EQ(time_, imu_tracker_->time());
00051 }
00052
00053 Eigen::Vector3d angular_velocity_;
00054 std::unique_ptr<ImuTracker> imu_tracker_;
00055 Eigen::Vector3d linear_acceleration_;
00056 common::Time time_ = common::FromUniversal(12345678);
00057 };
00058
00059 TEST_F(ImuTrackerTest, IntegrateYawRotation) {
00060 angular_velocity_ = Eigen::Vector3d(0, 0, 0.3);
00061 AdvanceImu();
00062 Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
00063 kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
00064 EXPECT_NEAR(0.,
00065 imu_tracker_->orientation().angularDistance(expected_orientation),
00066 kPrecision);
00067 }
00068
00069 TEST_F(ImuTrackerTest, IntegrateFullRotation) {
00070 angular_velocity_ = Eigen::Vector3d(0.1, 0.4, 0.1);
00071
00072
00073 imu_tracker_.reset(new ImuTracker(1e10 * kDuration, time_));
00074 AdvanceImu();
00075 Eigen::Quaterniond expected_orientation(Eigen::AngleAxisd(
00076 kDuration * angular_velocity_.norm(), angular_velocity_.normalized()));
00077 EXPECT_NEAR(0.,
00078 imu_tracker_->orientation().angularDistance(expected_orientation),
00079 kPrecision);
00080 }
00081
00082 TEST_F(ImuTrackerTest, LearnGravityVector) {
00083 linear_acceleration_ = Eigen::Vector3d(0.5, 0.3, 9.5);
00084 AdvanceImu();
00085 Eigen::Quaterniond expected_orientation;
00086 expected_orientation.setFromTwoVectors(linear_acceleration_,
00087 Eigen::Vector3d::UnitZ());
00088 EXPECT_NEAR(0.,
00089 imu_tracker_->orientation().angularDistance(expected_orientation),
00090 kPrecision);
00091 }
00092
00093 }
00094 }
00095 }