imu_tracker.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/mapping/imu_tracker.h"
00018 
00019 #include <cmath>
00020 #include <limits>
00021 
00022 #include "cartographer/common/math.h"
00023 #include "cartographer/transform/transform.h"
00024 #include "glog/logging.h"
00025 
00026 namespace cartographer {
00027 namespace mapping {
00028 
00029 ImuTracker::ImuTracker(const double imu_gravity_time_constant,
00030                        const common::Time time)
00031     : imu_gravity_time_constant_(imu_gravity_time_constant),
00032       time_(time),
00033       last_linear_acceleration_time_(common::Time::min()),
00034       orientation_(Eigen::Quaterniond::Identity()),
00035       gravity_vector_(Eigen::Vector3d::UnitZ()),
00036       imu_angular_velocity_(Eigen::Vector3d::Zero()) {}
00037 
00038 void ImuTracker::Advance(const common::Time time) {
00039   CHECK_LE(time_, time);
00040   const double delta_t = common::ToSeconds(time - time_);
00041   const Eigen::Quaterniond rotation =
00042       transform::AngleAxisVectorToRotationQuaternion(
00043           Eigen::Vector3d(imu_angular_velocity_ * delta_t));
00044   orientation_ = (orientation_ * rotation).normalized();
00045   gravity_vector_ = rotation.conjugate() * gravity_vector_;
00046   time_ = time;
00047 }
00048 
00049 void ImuTracker::AddImuLinearAccelerationObservation(
00050     const Eigen::Vector3d& imu_linear_acceleration) {
00051   // Update the 'gravity_vector_' with an exponential moving average using the
00052   // 'imu_gravity_time_constant'.
00053   const double delta_t =
00054       last_linear_acceleration_time_ > common::Time::min()
00055           ? common::ToSeconds(time_ - last_linear_acceleration_time_)
00056           : std::numeric_limits<double>::infinity();
00057   last_linear_acceleration_time_ = time_;
00058   const double alpha = 1. - std::exp(-delta_t / imu_gravity_time_constant_);
00059   gravity_vector_ =
00060       (1. - alpha) * gravity_vector_ + alpha * imu_linear_acceleration;
00061   // Change the 'orientation_' so that it agrees with the current
00062   // 'gravity_vector_'.
00063   const Eigen::Quaterniond rotation = Eigen::Quaterniond::FromTwoVectors(
00064       gravity_vector_, orientation_.conjugate() * Eigen::Vector3d::UnitZ());
00065   orientation_ = (orientation_ * rotation).normalized();
00066   CHECK_GT((orientation_ * gravity_vector_).z(), 0.);
00067   CHECK_GT((orientation_ * gravity_vector_).normalized().z(), 0.99);
00068 }
00069 
00070 void ImuTracker::AddImuAngularVelocityObservation(
00071     const Eigen::Vector3d& imu_angular_velocity) {
00072   imu_angular_velocity_ = imu_angular_velocity;
00073 }
00074 
00075 }  // namespace mapping
00076 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35