pose_extrapolator.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 
19 #include <algorithm>
20 
23 #include "glog/logging.h"
24 
25 namespace cartographer {
26 namespace mapping {
27 
29  double imu_gravity_time_constant)
30  : pose_queue_duration_(pose_queue_duration),
31  gravity_time_constant_(imu_gravity_time_constant),
32  cached_extrapolated_pose_{common::Time::min(),
34 
35 std::unique_ptr<PoseExtrapolator> PoseExtrapolator::InitializeWithImu(
36  const common::Duration pose_queue_duration,
37  const double imu_gravity_time_constant, const sensor::ImuData& imu_data) {
38  auto extrapolator = common::make_unique<PoseExtrapolator>(
39  pose_queue_duration, imu_gravity_time_constant);
40  extrapolator->AddImuData(imu_data);
41  extrapolator->imu_tracker_ =
42  common::make_unique<ImuTracker>(imu_gravity_time_constant, imu_data.time);
43  extrapolator->imu_tracker_->AddImuLinearAccelerationObservation(
44  imu_data.linear_acceleration);
45  extrapolator->imu_tracker_->AddImuAngularVelocityObservation(
46  imu_data.angular_velocity);
47  extrapolator->imu_tracker_->Advance(imu_data.time);
48  extrapolator->AddPose(
49  imu_data.time,
50  transform::Rigid3d::Rotation(extrapolator->imu_tracker_->orientation()));
51  return extrapolator;
52 }
53 
55  if (timed_pose_queue_.empty()) {
56  return common::Time::min();
57  }
58  return timed_pose_queue_.back().time;
59 }
60 
63  return common::Time::min();
64  }
65  return extrapolation_imu_tracker_->time();
66 }
67 
69  const transform::Rigid3d& pose) {
70  if (imu_tracker_ == nullptr) {
71  common::Time tracker_start = time;
72  if (!imu_data_.empty()) {
73  tracker_start = std::min(tracker_start, imu_data_.front().time);
74  }
75  imu_tracker_ =
76  common::make_unique<ImuTracker>(gravity_time_constant_, tracker_start);
77  }
78  timed_pose_queue_.push_back(TimedPose{time, pose});
79  while (timed_pose_queue_.size() > 2 &&
80  timed_pose_queue_[1].time <= time - pose_queue_duration_) {
81  timed_pose_queue_.pop_front();
82  }
84  AdvanceImuTracker(time, imu_tracker_.get());
85  TrimImuData();
87  odometry_imu_tracker_ = common::make_unique<ImuTracker>(*imu_tracker_);
88  extrapolation_imu_tracker_ = common::make_unique<ImuTracker>(*imu_tracker_);
89 }
90 
92  CHECK(timed_pose_queue_.empty() ||
93  imu_data.time >= timed_pose_queue_.back().time);
94  imu_data_.push_back(imu_data);
95  TrimImuData();
96 }
97 
99  const sensor::OdometryData& odometry_data) {
100  CHECK(timed_pose_queue_.empty() ||
101  odometry_data.time >= timed_pose_queue_.back().time);
102  odometry_data_.push_back(odometry_data);
104  if (odometry_data_.size() < 2) {
105  return;
106  }
107  // TODO(whess): Improve by using more than just the last two odometry poses.
108  // Compute extrapolation in the tracking frame.
109  const sensor::OdometryData& odometry_data_oldest = odometry_data_.front();
110  const sensor::OdometryData& odometry_data_newest = odometry_data_.back();
111  const double odometry_time_delta =
112  common::ToSeconds(odometry_data_oldest.time - odometry_data_newest.time);
113  const transform::Rigid3d odometry_pose_delta =
114  odometry_data_newest.pose.inverse() * odometry_data_oldest.pose;
117  odometry_pose_delta.rotation()) /
118  odometry_time_delta;
119  if (timed_pose_queue_.empty()) {
120  return;
121  }
122  const Eigen::Vector3d
123  linear_velocity_in_tracking_frame_at_newest_odometry_time =
124  odometry_pose_delta.translation() / odometry_time_delta;
125  const Eigen::Quaterniond orientation_at_newest_odometry_time =
126  timed_pose_queue_.back().pose.rotation() *
127  ExtrapolateRotation(odometry_data_newest.time,
128  odometry_imu_tracker_.get());
130  orientation_at_newest_odometry_time *
131  linear_velocity_in_tracking_frame_at_newest_odometry_time;
132 }
133 
135  const TimedPose& newest_timed_pose = timed_pose_queue_.back();
136  CHECK_GE(time, newest_timed_pose.time);
137  if (cached_extrapolated_pose_.time != time) {
138  const Eigen::Vector3d translation =
139  ExtrapolateTranslation(time) + newest_timed_pose.pose.translation();
140  const Eigen::Quaterniond rotation =
141  newest_timed_pose.pose.rotation() *
144  TimedPose{time, transform::Rigid3d{translation, rotation}};
145  }
147 }
148 
150  const common::Time time) {
151  ImuTracker imu_tracker = *imu_tracker_;
152  AdvanceImuTracker(time, &imu_tracker);
153  return imu_tracker.orientation();
154 }
155 
157  if (timed_pose_queue_.size() < 2) {
158  // We need two poses to estimate velocities.
159  return;
160  }
161  CHECK(!timed_pose_queue_.empty());
162  const TimedPose& newest_timed_pose = timed_pose_queue_.back();
163  const auto newest_time = newest_timed_pose.time;
164  const TimedPose& oldest_timed_pose = timed_pose_queue_.front();
165  const auto oldest_time = oldest_timed_pose.time;
166  const double queue_delta = common::ToSeconds(newest_time - oldest_time);
167  if (queue_delta < 0.001) { // 1 ms
168  LOG(WARNING) << "Queue too short for velocity estimation. Queue duration: "
169  << queue_delta << " ms";
170  return;
171  }
172  const transform::Rigid3d& newest_pose = newest_timed_pose.pose;
173  const transform::Rigid3d& oldest_pose = oldest_timed_pose.pose;
175  (newest_pose.translation() - oldest_pose.translation()) / queue_delta;
178  oldest_pose.rotation().inverse() * newest_pose.rotation()) /
179  queue_delta;
180 }
181 
183  while (imu_data_.size() > 1 && !timed_pose_queue_.empty() &&
184  imu_data_[1].time <= timed_pose_queue_.back().time) {
185  imu_data_.pop_front();
186  }
187 }
188 
190  while (odometry_data_.size() > 2 && !timed_pose_queue_.empty() &&
191  odometry_data_[1].time <= timed_pose_queue_.back().time) {
192  odometry_data_.pop_front();
193  }
194 }
195 
197  ImuTracker* const imu_tracker) const {
198  CHECK_GE(time, imu_tracker->time());
199  if (imu_data_.empty() || time < imu_data_.front().time) {
200  // There is no IMU data until 'time', so we advance the ImuTracker and use
201  // the angular velocities from poses and fake gravity to help 2D stability.
202  imu_tracker->Advance(time);
203  imu_tracker->AddImuLinearAccelerationObservation(Eigen::Vector3d::UnitZ());
207  return;
208  }
209  if (imu_tracker->time() < imu_data_.front().time) {
210  // Advance to the beginning of 'imu_data_'.
211  imu_tracker->Advance(imu_data_.front().time);
212  }
213  auto it = std::lower_bound(
214  imu_data_.begin(), imu_data_.end(), imu_tracker->time(),
215  [](const sensor::ImuData& imu_data, const common::Time& time) {
216  return imu_data.time < time;
217  });
218  while (it != imu_data_.end() && it->time < time) {
219  imu_tracker->Advance(it->time);
220  imu_tracker->AddImuLinearAccelerationObservation(it->linear_acceleration);
221  imu_tracker->AddImuAngularVelocityObservation(it->angular_velocity);
222  ++it;
223  }
224  imu_tracker->Advance(time);
225 }
226 
228  const common::Time time, ImuTracker* const imu_tracker) const {
229  CHECK_GE(time, imu_tracker->time());
230  AdvanceImuTracker(time, imu_tracker);
231  const Eigen::Quaterniond last_orientation = imu_tracker_->orientation();
232  return last_orientation.inverse() * imu_tracker->orientation();
233 }
234 
236  const TimedPose& newest_timed_pose = timed_pose_queue_.back();
237  const double extrapolation_delta =
238  common::ToSeconds(time - newest_timed_pose.time);
239  if (odometry_data_.size() < 2) {
240  return extrapolation_delta * linear_velocity_from_poses_;
241  }
242  return extrapolation_delta * linear_velocity_from_odometry_;
243 }
244 
245 } // namespace mapping
246 } // namespace cartographer
std::unique_ptr< ImuTracker > extrapolation_imu_tracker_
static Rigid3 Rotation(const AngleAxis &angle_axis)
Eigen::Matrix< T, 3, 1 > RotationQuaternionToAngleAxisVector(const Eigen::Quaternion< T > &quaternion)
Definition: transform.h:60
static std::unique_ptr< PoseExtrapolator > InitializeWithImu(common::Duration pose_queue_duration, double imu_gravity_time_constant, const sensor::ImuData &imu_data)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
const Quaternion & rotation() const
transform::Rigid3d ExtrapolatePose(common::Time time)
std::deque< sensor::ImuData > imu_data_
static time_point time
void AddImuLinearAccelerationObservation(const Eigen::Vector3d &imu_linear_acceleration)
Definition: imu_tracker.cc:49
common::Time time() const
Definition: imu_tracker.h:44
UniversalTimeScaleClock::duration Duration
Definition: time.h:43
const Vector & translation() const
Eigen::Quaterniond orientation() const
Definition: imu_tracker.h:47
PoseExtrapolator(common::Duration pose_queue_duration, double imu_gravity_time_constant)
void AddImuAngularVelocityObservation(const Eigen::Vector3d &imu_angular_velocity)
Definition: imu_tracker.cc:70
void AddOdometryData(const sensor::OdometryData &odometry_data)
double ToSeconds(const Duration duration)
Definition: time.cc:29
Eigen::Quaterniond ExtrapolateRotation(common::Time time, ImuTracker *imu_tracker) const
std::unique_ptr< ImuTracker > imu_tracker_
Eigen::Quaterniond EstimateGravityOrientation(common::Time time)
void AddPose(common::Time time, const transform::Rigid3d &pose)
void AddImuData(const sensor::ImuData &imu_data)
transform::Rigid3d pose
std::deque< sensor::OdometryData > odometry_data_
void AdvanceImuTracker(common::Time time, ImuTracker *imu_tracker) const
void Advance(common::Time time)
Definition: imu_tracker.cc:38
std::unique_ptr< ImuTracker > odometry_imu_tracker_
Eigen::Vector3d angular_velocity
Definition: imu_data.h:30
Eigen::Vector3d ExtrapolateTranslation(common::Time time)
Eigen::Vector3d linear_acceleration
Definition: imu_data.h:29


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