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/pose_extrapolator.h"
00018
00019 #include <algorithm>
00020
00021 #include "absl/memory/memory.h"
00022 #include "cartographer/transform/transform.h"
00023 #include "glog/logging.h"
00024
00025 namespace cartographer {
00026 namespace mapping {
00027
00028 PoseExtrapolator::PoseExtrapolator(const common::Duration pose_queue_duration,
00029 double imu_gravity_time_constant)
00030 : pose_queue_duration_(pose_queue_duration),
00031 gravity_time_constant_(imu_gravity_time_constant),
00032 cached_extrapolated_pose_{common::Time::min(),
00033 transform::Rigid3d::Identity()} {}
00034
00035 std::unique_ptr<PoseExtrapolator> PoseExtrapolator::InitializeWithImu(
00036 const common::Duration pose_queue_duration,
00037 const double imu_gravity_time_constant, const sensor::ImuData& imu_data) {
00038 auto extrapolator = absl::make_unique<PoseExtrapolator>(
00039 pose_queue_duration, imu_gravity_time_constant);
00040 extrapolator->AddImuData(imu_data);
00041 extrapolator->imu_tracker_ =
00042 absl::make_unique<ImuTracker>(imu_gravity_time_constant, imu_data.time);
00043 extrapolator->imu_tracker_->AddImuLinearAccelerationObservation(
00044 imu_data.linear_acceleration);
00045 extrapolator->imu_tracker_->AddImuAngularVelocityObservation(
00046 imu_data.angular_velocity);
00047 extrapolator->imu_tracker_->Advance(imu_data.time);
00048 extrapolator->AddPose(
00049 imu_data.time,
00050 transform::Rigid3d::Rotation(extrapolator->imu_tracker_->orientation()));
00051 return extrapolator;
00052 }
00053
00054 common::Time PoseExtrapolator::GetLastPoseTime() const {
00055 if (timed_pose_queue_.empty()) {
00056 return common::Time::min();
00057 }
00058 return timed_pose_queue_.back().time;
00059 }
00060
00061 common::Time PoseExtrapolator::GetLastExtrapolatedTime() const {
00062 if (!extrapolation_imu_tracker_) {
00063 return common::Time::min();
00064 }
00065 return extrapolation_imu_tracker_->time();
00066 }
00067
00068 void PoseExtrapolator::AddPose(const common::Time time,
00069 const transform::Rigid3d& pose) {
00070 if (imu_tracker_ == nullptr) {
00071 common::Time tracker_start = time;
00072 if (!imu_data_.empty()) {
00073 tracker_start = std::min(tracker_start, imu_data_.front().time);
00074 }
00075 imu_tracker_ =
00076 absl::make_unique<ImuTracker>(gravity_time_constant_, tracker_start);
00077 }
00078 timed_pose_queue_.push_back(TimedPose{time, pose});
00079 while (timed_pose_queue_.size() > 2 &&
00080 timed_pose_queue_[1].time <= time - pose_queue_duration_) {
00081 timed_pose_queue_.pop_front();
00082 }
00083 UpdateVelocitiesFromPoses();
00084 AdvanceImuTracker(time, imu_tracker_.get());
00085 TrimImuData();
00086 TrimOdometryData();
00087 odometry_imu_tracker_ = absl::make_unique<ImuTracker>(*imu_tracker_);
00088 extrapolation_imu_tracker_ = absl::make_unique<ImuTracker>(*imu_tracker_);
00089 }
00090
00091 void PoseExtrapolator::AddImuData(const sensor::ImuData& imu_data) {
00092 CHECK(timed_pose_queue_.empty() ||
00093 imu_data.time >= timed_pose_queue_.back().time);
00094 imu_data_.push_back(imu_data);
00095 TrimImuData();
00096 }
00097
00098 void PoseExtrapolator::AddOdometryData(
00099 const sensor::OdometryData& odometry_data) {
00100 CHECK(timed_pose_queue_.empty() ||
00101 odometry_data.time >= timed_pose_queue_.back().time);
00102 odometry_data_.push_back(odometry_data);
00103 TrimOdometryData();
00104 if (odometry_data_.size() < 2) {
00105 return;
00106 }
00107
00108
00109 const sensor::OdometryData& odometry_data_oldest = odometry_data_.front();
00110 const sensor::OdometryData& odometry_data_newest = odometry_data_.back();
00111 const double odometry_time_delta =
00112 common::ToSeconds(odometry_data_oldest.time - odometry_data_newest.time);
00113 const transform::Rigid3d odometry_pose_delta =
00114 odometry_data_newest.pose.inverse() * odometry_data_oldest.pose;
00115 angular_velocity_from_odometry_ =
00116 transform::RotationQuaternionToAngleAxisVector(
00117 odometry_pose_delta.rotation()) /
00118 odometry_time_delta;
00119 if (timed_pose_queue_.empty()) {
00120 return;
00121 }
00122 const Eigen::Vector3d
00123 linear_velocity_in_tracking_frame_at_newest_odometry_time =
00124 odometry_pose_delta.translation() / odometry_time_delta;
00125 const Eigen::Quaterniond orientation_at_newest_odometry_time =
00126 timed_pose_queue_.back().pose.rotation() *
00127 ExtrapolateRotation(odometry_data_newest.time,
00128 odometry_imu_tracker_.get());
00129 linear_velocity_from_odometry_ =
00130 orientation_at_newest_odometry_time *
00131 linear_velocity_in_tracking_frame_at_newest_odometry_time;
00132 }
00133
00134 transform::Rigid3d PoseExtrapolator::ExtrapolatePose(const common::Time time) {
00135 const TimedPose& newest_timed_pose = timed_pose_queue_.back();
00136 CHECK_GE(time, newest_timed_pose.time);
00137 if (cached_extrapolated_pose_.time != time) {
00138 const Eigen::Vector3d translation =
00139 ExtrapolateTranslation(time) + newest_timed_pose.pose.translation();
00140 const Eigen::Quaterniond rotation =
00141 newest_timed_pose.pose.rotation() *
00142 ExtrapolateRotation(time, extrapolation_imu_tracker_.get());
00143 cached_extrapolated_pose_ =
00144 TimedPose{time, transform::Rigid3d{translation, rotation}};
00145 }
00146 return cached_extrapolated_pose_.pose;
00147 }
00148
00149 Eigen::Quaterniond PoseExtrapolator::EstimateGravityOrientation(
00150 const common::Time time) {
00151 ImuTracker imu_tracker = *imu_tracker_;
00152 AdvanceImuTracker(time, &imu_tracker);
00153 return imu_tracker.orientation();
00154 }
00155
00156 void PoseExtrapolator::UpdateVelocitiesFromPoses() {
00157 if (timed_pose_queue_.size() < 2) {
00158
00159 return;
00160 }
00161 CHECK(!timed_pose_queue_.empty());
00162 const TimedPose& newest_timed_pose = timed_pose_queue_.back();
00163 const auto newest_time = newest_timed_pose.time;
00164 const TimedPose& oldest_timed_pose = timed_pose_queue_.front();
00165 const auto oldest_time = oldest_timed_pose.time;
00166 const double queue_delta = common::ToSeconds(newest_time - oldest_time);
00167 if (queue_delta < common::ToSeconds(pose_queue_duration_)) {
00168 LOG(WARNING) << "Queue too short for velocity estimation. Queue duration: "
00169 << queue_delta << " s";
00170 return;
00171 }
00172 const transform::Rigid3d& newest_pose = newest_timed_pose.pose;
00173 const transform::Rigid3d& oldest_pose = oldest_timed_pose.pose;
00174 linear_velocity_from_poses_ =
00175 (newest_pose.translation() - oldest_pose.translation()) / queue_delta;
00176 angular_velocity_from_poses_ =
00177 transform::RotationQuaternionToAngleAxisVector(
00178 oldest_pose.rotation().inverse() * newest_pose.rotation()) /
00179 queue_delta;
00180 }
00181
00182 void PoseExtrapolator::TrimImuData() {
00183 while (imu_data_.size() > 1 && !timed_pose_queue_.empty() &&
00184 imu_data_[1].time <= timed_pose_queue_.back().time) {
00185 imu_data_.pop_front();
00186 }
00187 }
00188
00189 void PoseExtrapolator::TrimOdometryData() {
00190 while (odometry_data_.size() > 2 && !timed_pose_queue_.empty() &&
00191 odometry_data_[1].time <= timed_pose_queue_.back().time) {
00192 odometry_data_.pop_front();
00193 }
00194 }
00195
00196 void PoseExtrapolator::AdvanceImuTracker(const common::Time time,
00197 ImuTracker* const imu_tracker) const {
00198 CHECK_GE(time, imu_tracker->time());
00199 if (imu_data_.empty() || time < imu_data_.front().time) {
00200
00201
00202 imu_tracker->Advance(time);
00203 imu_tracker->AddImuLinearAccelerationObservation(Eigen::Vector3d::UnitZ());
00204 imu_tracker->AddImuAngularVelocityObservation(
00205 odometry_data_.size() < 2 ? angular_velocity_from_poses_
00206 : angular_velocity_from_odometry_);
00207 return;
00208 }
00209 if (imu_tracker->time() < imu_data_.front().time) {
00210
00211 imu_tracker->Advance(imu_data_.front().time);
00212 }
00213 auto it = std::lower_bound(
00214 imu_data_.begin(), imu_data_.end(), imu_tracker->time(),
00215 [](const sensor::ImuData& imu_data, const common::Time& time) {
00216 return imu_data.time < time;
00217 });
00218 while (it != imu_data_.end() && it->time < time) {
00219 imu_tracker->Advance(it->time);
00220 imu_tracker->AddImuLinearAccelerationObservation(it->linear_acceleration);
00221 imu_tracker->AddImuAngularVelocityObservation(it->angular_velocity);
00222 ++it;
00223 }
00224 imu_tracker->Advance(time);
00225 }
00226
00227 Eigen::Quaterniond PoseExtrapolator::ExtrapolateRotation(
00228 const common::Time time, ImuTracker* const imu_tracker) const {
00229 CHECK_GE(time, imu_tracker->time());
00230 AdvanceImuTracker(time, imu_tracker);
00231 const Eigen::Quaterniond last_orientation = imu_tracker_->orientation();
00232 return last_orientation.inverse() * imu_tracker->orientation();
00233 }
00234
00235 Eigen::Vector3d PoseExtrapolator::ExtrapolateTranslation(common::Time time) {
00236 const TimedPose& newest_timed_pose = timed_pose_queue_.back();
00237 const double extrapolation_delta =
00238 common::ToSeconds(time - newest_timed_pose.time);
00239 if (odometry_data_.size() < 2) {
00240 return extrapolation_delta * linear_velocity_from_poses_;
00241 }
00242 return extrapolation_delta * linear_velocity_from_odometry_;
00243 }
00244
00245 }
00246 }