pose_graph_3d.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 #include <cmath>
21 #include <cstdio>
22 #include <functional>
23 #include <iomanip>
24 #include <iostream>
25 #include <limits>
26 #include <memory>
27 #include <sstream>
28 #include <string>
29 
30 #include "Eigen/Eigenvalues"
33 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h"
37 #include "glog/logging.h"
38 
39 namespace cartographer {
40 namespace mapping {
41 
43  const proto::PoseGraphOptions& options,
44  std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem,
45  common::ThreadPool* thread_pool)
46  : options_(options),
47  optimization_problem_(std::move(optimization_problem)),
48  constraint_builder_(options_.constraint_builder_options(), thread_pool) {}
49 
52  common::MutexLocker locker(&mutex_);
53  CHECK(work_queue_ == nullptr);
54 }
55 
57  const int trajectory_id, const common::Time time,
58  const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps) {
59  CHECK(!insertion_submaps.empty());
60  const auto& submap_data = optimization_problem_->submap_data();
61  if (insertion_submaps.size() == 1) {
62  // If we don't already have an entry for the first submap, add one.
63  if (submap_data.SizeOfTrajectoryOrZero(trajectory_id) == 0) {
64  if (initial_trajectory_poses_.count(trajectory_id) > 0) {
66  trajectory_id,
67  initial_trajectory_poses_.at(trajectory_id).to_trajectory_id, time);
68  }
69  optimization_problem_->AddSubmap(
70  trajectory_id,
71  ComputeLocalToGlobalTransform(global_submap_poses_, trajectory_id) *
72  insertion_submaps[0]->local_pose());
73  }
74  CHECK_EQ(1, submap_data.SizeOfTrajectoryOrZero(trajectory_id));
75  const SubmapId submap_id{trajectory_id, 0};
76  CHECK(submap_data_.at(submap_id).submap == insertion_submaps.front());
77  return {submap_id};
78  }
79  CHECK_EQ(2, insertion_submaps.size());
80  const auto end_it = submap_data.EndOfTrajectory(trajectory_id);
81  CHECK(submap_data.BeginOfTrajectory(trajectory_id) != end_it);
82  const SubmapId last_submap_id = std::prev(end_it)->id;
83  if (submap_data_.at(last_submap_id).submap == insertion_submaps.front()) {
84  // In this case, 'last_submap_id' is the ID of 'insertions_submaps.front()'
85  // and 'insertions_submaps.back()' is new.
86  const auto& first_submap_pose = submap_data.at(last_submap_id).global_pose;
87  optimization_problem_->AddSubmap(
88  trajectory_id, first_submap_pose *
89  insertion_submaps[0]->local_pose().inverse() *
90  insertion_submaps[1]->local_pose());
91  return {last_submap_id,
92  SubmapId{trajectory_id, last_submap_id.submap_index + 1}};
93  }
94  CHECK(submap_data_.at(last_submap_id).submap == insertion_submaps.back());
95  const SubmapId front_submap_id{trajectory_id,
96  last_submap_id.submap_index - 1};
97  CHECK(submap_data_.at(front_submap_id).submap == insertion_submaps.front());
98  return {front_submap_id, last_submap_id};
99 }
100 
102  std::shared_ptr<const TrajectoryNode::Data> constant_data,
103  const int trajectory_id,
104  const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps) {
105  const transform::Rigid3d optimized_pose(
106  GetLocalToGlobalTransform(trajectory_id) * constant_data->local_pose);
107 
108  common::MutexLocker locker(&mutex_);
109  AddTrajectoryIfNeeded(trajectory_id);
110  const NodeId node_id = trajectory_nodes_.Append(
111  trajectory_id, TrajectoryNode{constant_data, optimized_pose});
112  ++num_trajectory_nodes_;
113 
114  // Test if the 'insertion_submap.back()' is one we never saw before.
115  if (submap_data_.SizeOfTrajectoryOrZero(trajectory_id) == 0 ||
116  std::prev(submap_data_.EndOfTrajectory(trajectory_id))->data.submap !=
117  insertion_submaps.back()) {
118  // We grow 'submap_data_' as needed. This code assumes that the first
119  // time we see a new submap is as 'insertion_submaps.back()'.
120  const SubmapId submap_id =
121  submap_data_.Append(trajectory_id, InternalSubmapData());
122  submap_data_.at(submap_id).submap = insertion_submaps.back();
123  }
124 
125  // We have to check this here, because it might have changed by the time we
126  // execute the lambda.
127  const bool newly_finished_submap = insertion_submaps.front()->finished();
128  AddWorkItem([=]() REQUIRES(mutex_) {
129  ComputeConstraintsForNode(node_id, insertion_submaps,
130  newly_finished_submap);
131  });
132  return node_id;
133 }
134 
135 void PoseGraph3D::AddWorkItem(const std::function<void()>& work_item) {
136  if (work_queue_ == nullptr) {
137  work_item();
138  } else {
139  work_queue_->push_back(work_item);
140  }
141 }
142 
143 void PoseGraph3D::AddTrajectoryIfNeeded(const int trajectory_id) {
144  trajectory_connectivity_state_.Add(trajectory_id);
145  // Make sure we have a sampler for this trajectory.
146  if (!global_localization_samplers_[trajectory_id]) {
147  global_localization_samplers_[trajectory_id] =
148  common::make_unique<common::FixedRatioSampler>(
149  options_.global_sampling_ratio());
150  }
151 }
152 
153 void PoseGraph3D::AddImuData(const int trajectory_id,
154  const sensor::ImuData& imu_data) {
155  common::MutexLocker locker(&mutex_);
156  AddWorkItem([=]() REQUIRES(mutex_) {
157  optimization_problem_->AddImuData(trajectory_id, imu_data);
158  });
159 }
160 
161 void PoseGraph3D::AddOdometryData(const int trajectory_id,
162  const sensor::OdometryData& odometry_data) {
163  common::MutexLocker locker(&mutex_);
164  AddWorkItem([=]() REQUIRES(mutex_) {
165  optimization_problem_->AddOdometryData(trajectory_id, odometry_data);
166  });
167 }
168 
170  const int trajectory_id,
171  const sensor::FixedFramePoseData& fixed_frame_pose_data) {
172  common::MutexLocker locker(&mutex_);
173  AddWorkItem([=]() REQUIRES(mutex_) {
174  optimization_problem_->AddFixedFramePoseData(trajectory_id,
175  fixed_frame_pose_data);
176  });
177 }
178 
179 void PoseGraph3D::AddLandmarkData(int trajectory_id,
180  const sensor::LandmarkData& landmark_data)
181  EXCLUDES(mutex_) {
182  common::MutexLocker locker(&mutex_);
183  AddWorkItem([=]() REQUIRES(mutex_) {
184  for (const auto& observation : landmark_data.landmark_observations) {
185  landmark_nodes_[observation.id].landmark_observations.emplace_back(
186  PoseGraphInterface::LandmarkNode::LandmarkObservation{
187  trajectory_id, landmark_data.time,
188  observation.landmark_to_tracking_transform,
189  observation.translation_weight, observation.rotation_weight});
190  }
191  });
192 }
193 
195  const SubmapId& submap_id) {
196  CHECK(submap_data_.at(submap_id).state == SubmapState::kFinished);
197 
198  const transform::Rigid3d global_node_pose =
199  optimization_problem_->node_data().at(node_id).global_pose;
200 
201  const transform::Rigid3d global_submap_pose =
202  optimization_problem_->submap_data().at(submap_id).global_pose;
203 
204  const transform::Rigid3d global_submap_pose_inverse =
205  global_submap_pose.inverse();
206 
207  std::vector<TrajectoryNode> submap_nodes;
208  for (const NodeId& submap_node_id : submap_data_.at(submap_id).node_ids) {
209  submap_nodes.push_back(
210  TrajectoryNode{trajectory_nodes_.at(submap_node_id).constant_data,
211  global_submap_pose_inverse *
212  trajectory_nodes_.at(submap_node_id).global_pose});
213  }
214 
215  const common::Time node_time = GetLatestNodeTime(node_id, submap_id);
216  const common::Time last_connection_time =
218  node_id.trajectory_id, submap_id.trajectory_id);
219  if (node_id.trajectory_id == submap_id.trajectory_id ||
220  node_time <
221  last_connection_time +
223  options_.global_constraint_search_after_n_seconds())) {
224  // If the node and the submap belong to the same trajectory or if there has
225  // been a recent global constraint that ties that node's trajectory to the
226  // submap's trajectory, it suffices to do a match constrained to a local
227  // search window.
228  constraint_builder_.MaybeAddConstraint(
229  submap_id, submap_data_.at(submap_id).submap.get(), node_id,
230  trajectory_nodes_.at(node_id).constant_data.get(), submap_nodes,
231  global_node_pose, global_submap_pose);
232  } else if (global_localization_samplers_[node_id.trajectory_id]->Pulse()) {
233  // In this situation, 'global_node_pose' and 'global_submap_pose' have
234  // orientations agreeing on gravity. Their relationship regarding yaw is
235  // arbitrary. Finding the correct yaw component will be handled by the
236  // matching procedure in the FastCorrelativeScanMatcher, and the given yaw
237  // is essentially ignored.
238  constraint_builder_.MaybeAddGlobalConstraint(
239  submap_id, submap_data_.at(submap_id).submap.get(), node_id,
240  trajectory_nodes_.at(node_id).constant_data.get(), submap_nodes,
241  global_node_pose.rotation(), global_submap_pose.rotation());
242  }
243 }
244 
246  const auto& submap_data = submap_data_.at(submap_id);
247  for (const auto& node_id_data : optimization_problem_->node_data()) {
248  const NodeId& node_id = node_id_data.id;
249  if (submap_data.node_ids.count(node_id) == 0) {
250  ComputeConstraint(node_id, submap_id);
251  }
252  }
253 }
254 
256  const NodeId& node_id,
257  std::vector<std::shared_ptr<const Submap3D>> insertion_submaps,
258  const bool newly_finished_submap) {
259  const auto& constant_data = trajectory_nodes_.at(node_id).constant_data;
260  const std::vector<SubmapId> submap_ids = InitializeGlobalSubmapPoses(
261  node_id.trajectory_id, constant_data->time, insertion_submaps);
262  CHECK_EQ(submap_ids.size(), insertion_submaps.size());
263  const SubmapId matching_id = submap_ids.front();
264  const transform::Rigid3d& local_pose = constant_data->local_pose;
265  const transform::Rigid3d global_pose =
266  optimization_problem_->submap_data().at(matching_id).global_pose *
267  insertion_submaps.front()->local_pose().inverse() * local_pose;
268  optimization_problem_->AddTrajectoryNode(
269  matching_id.trajectory_id,
270  optimization::NodeSpec3D{constant_data->time, local_pose, global_pose});
271  for (size_t i = 0; i < insertion_submaps.size(); ++i) {
272  const SubmapId submap_id = submap_ids[i];
273  // Even if this was the last node added to 'submap_id', the submap will only
274  // be marked as finished in 'submap_data_' further below.
275  CHECK(submap_data_.at(submap_id).state == SubmapState::kActive);
276  submap_data_.at(submap_id).node_ids.emplace(node_id);
277  const transform::Rigid3d constraint_transform =
278  insertion_submaps[i]->local_pose().inverse() * local_pose;
279  constraints_.push_back(
280  Constraint{submap_id,
281  node_id,
282  {constraint_transform, options_.matcher_translation_weight(),
283  options_.matcher_rotation_weight()},
285  }
286 
287  for (const auto& submap_id_data : submap_data_) {
288  if (submap_id_data.data.state == SubmapState::kFinished) {
289  CHECK_EQ(submap_id_data.data.node_ids.count(node_id), 0);
290  ComputeConstraint(node_id, submap_id_data.id);
291  }
292  }
293 
294  if (newly_finished_submap) {
295  const SubmapId finished_submap_id = submap_ids.front();
296  InternalSubmapData& finished_submap_data =
297  submap_data_.at(finished_submap_id);
298  CHECK(finished_submap_data.state == SubmapState::kActive);
299  finished_submap_data.state = SubmapState::kFinished;
300  // We have a new completed submap, so we look into adding constraints for
301  // old nodes.
302  ComputeConstraintsForOldNodes(finished_submap_id);
303  }
304  constraint_builder_.NotifyEndOfNode();
305  ++num_nodes_since_last_loop_closure_;
306  CHECK(!run_loop_closure_);
307  if (options_.optimize_every_n_nodes() > 0 &&
308  num_nodes_since_last_loop_closure_ > options_.optimize_every_n_nodes()) {
310  }
311 }
312 
314  run_loop_closure_ = true;
315  // If there is a 'work_queue_' already, some other thread will take care.
316  if (work_queue_ == nullptr) {
317  work_queue_ = common::make_unique<std::deque<std::function<void()>>>();
318  constraint_builder_.WhenDone(
319  std::bind(&PoseGraph3D::HandleWorkQueue, this, std::placeholders::_1));
320  }
321 }
322 
324  const SubmapId& submap_id) const {
325  common::Time time = trajectory_nodes_.at(node_id).constant_data->time;
326  const InternalSubmapData& submap_data = submap_data_.at(submap_id);
327  if (!submap_data.node_ids.empty()) {
328  const NodeId last_submap_node_id =
329  *submap_data_.at(submap_id).node_ids.rbegin();
330  time = std::max(
331  time, trajectory_nodes_.at(last_submap_node_id).constant_data->time);
332  }
333  return time;
334 }
335 
338  const common::Time time =
339  GetLatestNodeTime(constraint.node_id, constraint.submap_id);
341  constraint.submap_id.trajectory_id,
342  time);
343 }
344 
347  {
348  common::MutexLocker locker(&mutex_);
349  constraints_.insert(constraints_.end(), result.begin(), result.end());
350  }
351  RunOptimization();
352 
354  std::map<int, NodeId> trajectory_id_to_last_optimized_node_id;
355  std::map<int, SubmapId> trajectory_id_to_last_optimized_submap_id;
356  {
357  common::MutexLocker locker(&mutex_);
358  const auto& submap_data = optimization_problem_->submap_data();
359  const auto& node_data = optimization_problem_->node_data();
360  for (const int trajectory_id : node_data.trajectory_ids()) {
361  trajectory_id_to_last_optimized_node_id[trajectory_id] =
362  std::prev(node_data.EndOfTrajectory(trajectory_id))->id;
363  trajectory_id_to_last_optimized_submap_id[trajectory_id] =
364  std::prev(submap_data.EndOfTrajectory(trajectory_id))->id;
365  }
366  }
368  trajectory_id_to_last_optimized_submap_id,
369  trajectory_id_to_last_optimized_node_id);
370  }
371 
372  common::MutexLocker locker(&mutex_);
373  for (const Constraint& constraint : result) {
374  UpdateTrajectoryConnectivity(constraint);
375  }
376  TrimmingHandle trimming_handle(this);
377  for (auto& trimmer : trimmers_) {
378  trimmer->Trim(&trimming_handle);
379  }
380  trimmers_.erase(
381  std::remove_if(trimmers_.begin(), trimmers_.end(),
382  [](std::unique_ptr<PoseGraphTrimmer>& trimmer) {
383  return trimmer->IsFinished();
384  }),
385  trimmers_.end());
386 
387  num_nodes_since_last_loop_closure_ = 0;
388  run_loop_closure_ = false;
389  while (!run_loop_closure_) {
390  if (work_queue_->empty()) {
391  work_queue_.reset();
392  return;
393  }
394  work_queue_->front()();
395  work_queue_->pop_front();
396  }
397  LOG(INFO) << "Remaining work items in queue: " << work_queue_->size();
398  // We have to optimize again.
399  constraint_builder_.WhenDone(
400  std::bind(&PoseGraph3D::HandleWorkQueue, this, std::placeholders::_1));
401 }
402 
404  bool notification = false;
405  common::MutexLocker locker(&mutex_);
406  const int num_finished_nodes_at_start =
407  constraint_builder_.GetNumFinishedNodes();
408  while (!locker.AwaitWithTimeout(
409  [this]() REQUIRES(mutex_) {
410  return ((constraint_builder_.GetNumFinishedNodes() ==
411  num_trajectory_nodes_) &&
412  !work_queue_);
413  },
414  common::FromSeconds(1.))) {
415  std::ostringstream progress_info;
416  progress_info << "Optimizing: " << std::fixed << std::setprecision(1)
417  << 100. *
418  (constraint_builder_.GetNumFinishedNodes() -
419  num_finished_nodes_at_start) /
420  (num_trajectory_nodes_ - num_finished_nodes_at_start)
421  << "%...";
422  std::cout << "\r\x1b[K" << progress_info.str() << std::flush;
423  }
424  std::cout << "\r\x1b[KOptimizing: Done. " << std::endl;
425  constraint_builder_.WhenDone(
426  [this,
427  &notification](const constraints::ConstraintBuilder3D::Result& result) {
428  common::MutexLocker locker(&mutex_);
429  constraints_.insert(constraints_.end(), result.begin(), result.end());
430  notification = true;
431  });
432  locker.Await([&notification]() { return notification; });
433 }
434 
435 void PoseGraph3D::FinishTrajectory(const int trajectory_id) {
436  common::MutexLocker locker(&mutex_);
437  AddWorkItem([this, trajectory_id]() REQUIRES(mutex_) {
438  CHECK_EQ(finished_trajectories_.count(trajectory_id), 0);
439  finished_trajectories_.insert(trajectory_id);
440 
441  for (const auto& submap : submap_data_.trajectory(trajectory_id)) {
442  submap_data_.at(submap.id).state = SubmapState::kFinished;
443  }
444  CHECK(!run_loop_closure_);
446  });
447 }
448 
449 bool PoseGraph3D::IsTrajectoryFinished(const int trajectory_id) const {
450  return finished_trajectories_.count(trajectory_id) > 0;
451 }
452 
453 void PoseGraph3D::FreezeTrajectory(const int trajectory_id) {
454  common::MutexLocker locker(&mutex_);
455  trajectory_connectivity_state_.Add(trajectory_id);
456  AddWorkItem([this, trajectory_id]() REQUIRES(mutex_) {
457  CHECK_EQ(frozen_trajectories_.count(trajectory_id), 0);
458  frozen_trajectories_.insert(trajectory_id);
459  });
460 }
461 
462 bool PoseGraph3D::IsTrajectoryFrozen(const int trajectory_id) const {
463  return frozen_trajectories_.count(trajectory_id) > 0;
464 }
465 
467  const transform::Rigid3d& global_submap_pose, const proto::Submap& submap) {
468  if (!submap.has_submap_3d()) {
469  return;
470  }
471 
472  const SubmapId submap_id = {submap.submap_id().trajectory_id(),
473  submap.submap_id().submap_index()};
474  std::shared_ptr<const Submap3D> submap_ptr =
475  std::make_shared<const Submap3D>(submap.submap_3d());
476 
477  common::MutexLocker locker(&mutex_);
479  submap_data_.Insert(submap_id, InternalSubmapData());
480  submap_data_.at(submap_id).submap = submap_ptr;
481  // Immediately show the submap at the 'global_submap_pose'.
482  global_submap_poses_.Insert(submap_id,
483  optimization::SubmapSpec3D{global_submap_pose});
484  AddWorkItem([this, submap_id, global_submap_pose]() REQUIRES(mutex_) {
485  submap_data_.at(submap_id).state = SubmapState::kFinished;
486  optimization_problem_->InsertSubmap(submap_id, global_submap_pose);
487  });
488 }
489 
491  const proto::Node& node) {
492  const NodeId node_id = {node.node_id().trajectory_id(),
493  node.node_id().node_index()};
494  std::shared_ptr<const TrajectoryNode::Data> constant_data =
495  std::make_shared<const TrajectoryNode::Data>(FromProto(node.node_data()));
496 
497  common::MutexLocker locker(&mutex_);
499  trajectory_nodes_.Insert(node_id, TrajectoryNode{constant_data, global_pose});
500 
501  AddWorkItem([this, node_id, global_pose]() REQUIRES(mutex_) {
502  const auto& constant_data = trajectory_nodes_.at(node_id).constant_data;
503  optimization_problem_->InsertTrajectoryNode(
504  node_id,
505  optimization::NodeSpec3D{constant_data->time, constant_data->local_pose,
506  global_pose});
507  });
508 }
509 
511  const proto::TrajectoryData& data) {
512  TrajectoryData trajectory_data;
513  trajectory_data.gravity_constant = data.gravity_constant();
514  trajectory_data.imu_calibration = {
515  {data.imu_calibration().w(), data.imu_calibration().x(),
516  data.imu_calibration().y(), data.imu_calibration().z()}};
517  if (data.has_fixed_frame_origin_in_map()) {
518  trajectory_data.fixed_frame_origin_in_map =
519  transform::ToRigid3(data.fixed_frame_origin_in_map());
520  }
521 
522  const int trajectory_id = data.trajectory_id();
523  common::MutexLocker locker(&mutex_);
524  AddWorkItem([this, trajectory_id, trajectory_data]() REQUIRES(mutex_) {
525  optimization_problem_->SetTrajectoryData(trajectory_id, trajectory_data);
526  });
527 }
528 
530  const SubmapId& submap_id) {
531  common::MutexLocker locker(&mutex_);
532  AddWorkItem([this, node_id, submap_id]() REQUIRES(mutex_) {
533  submap_data_.at(submap_id).node_ids.insert(node_id);
534  });
535 }
536 
538  const std::vector<Constraint>& constraints) {
539  common::MutexLocker locker(&mutex_);
540  AddWorkItem([this, constraints]() REQUIRES(mutex_) {
541  for (const auto& constraint : constraints) {
542  CHECK(trajectory_nodes_.Contains(constraint.node_id));
543  CHECK(submap_data_.Contains(constraint.submap_id));
544  CHECK(trajectory_nodes_.at(constraint.node_id).constant_data != nullptr);
545  CHECK(submap_data_.at(constraint.submap_id).submap != nullptr);
546  switch (constraint.tag) {
547  case Constraint::Tag::INTRA_SUBMAP:
548  CHECK(submap_data_.at(constraint.submap_id)
549  .node_ids.emplace(constraint.node_id)
550  .second);
551  break;
552  case Constraint::Tag::INTER_SUBMAP:
553  UpdateTrajectoryConnectivity(constraint);
554  break;
555  }
556  constraints_.push_back(constraint);
557  }
558  LOG(INFO) << "Loaded " << constraints.size() << " constraints.";
559  });
560 }
561 
562 void PoseGraph3D::AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) {
563  common::MutexLocker locker(&mutex_);
564  // C++11 does not allow us to move a unique_ptr into a lambda.
565  PoseGraphTrimmer* const trimmer_ptr = trimmer.release();
566  AddWorkItem([this, trimmer_ptr]()
567  REQUIRES(mutex_) { trimmers_.emplace_back(trimmer_ptr); });
568 }
569 
571  {
572  common::MutexLocker locker(&mutex_);
573  AddWorkItem([this]() REQUIRES(mutex_) {
574  optimization_problem_->SetMaxNumIterations(
575  options_.max_num_final_iterations());
577  });
578  AddWorkItem([this]() REQUIRES(mutex_) {
579  optimization_problem_->SetMaxNumIterations(
580  options_.optimization_problem_options()
581  .ceres_solver_options()
582  .max_num_iterations());
583  });
584  }
586 }
587 
589  common::Histogram rotational_residual;
590  common::Histogram translational_residual;
591  for (const Constraint& constraint : constraints_) {
592  if (constraint.tag == Constraint::Tag::INTRA_SUBMAP) {
593  const cartographer::transform::Rigid3d optimized_node_to_map =
594  trajectory_nodes_.at(constraint.node_id).global_pose;
595  const cartographer::transform::Rigid3d node_to_submap_constraint =
596  constraint.pose.zbar_ij;
597  const cartographer::transform::Rigid3d optimized_submap_to_map =
598  global_submap_poses_.at(constraint.submap_id).global_pose;
599  const cartographer::transform::Rigid3d optimized_node_to_submap =
600  optimized_submap_to_map.inverse() * optimized_node_to_map;
601  const cartographer::transform::Rigid3d residual =
602  node_to_submap_constraint.inverse() * optimized_node_to_submap;
603  rotational_residual.Add(
605  translational_residual.Add(residual.translation().norm());
606  }
607  }
608  LOG(INFO) << "Translational residuals histogram:\n"
609  << translational_residual.ToString(10);
610  LOG(INFO) << "Rotational residuals histogram:\n"
611  << rotational_residual.ToString(10);
612 }
613 
615  if (optimization_problem_->submap_data().empty()) {
616  return;
617  }
618 
619  // No other thread is accessing the optimization_problem_, constraints_,
620  // frozen_trajectories_ and landmark_nodes_ when executing the Solve. Solve is
621  // time consuming, so not taking the mutex before Solve to avoid blocking
622  // foreground processing.
623  optimization_problem_->Solve(constraints_, frozen_trajectories_,
624  landmark_nodes_);
625  common::MutexLocker locker(&mutex_);
626 
627  const auto& submap_data = optimization_problem_->submap_data();
628  const auto& node_data = optimization_problem_->node_data();
629  for (const int trajectory_id : node_data.trajectory_ids()) {
630  for (const auto& node : node_data.trajectory(trajectory_id)) {
631  trajectory_nodes_.at(node.id).global_pose = node.data.global_pose;
632  }
633 
634  // Extrapolate all point cloud poses that were not included in the
635  // 'optimization_problem_' yet.
636  const auto local_to_new_global =
637  ComputeLocalToGlobalTransform(submap_data, trajectory_id);
638  const auto local_to_old_global =
639  ComputeLocalToGlobalTransform(global_submap_poses_, trajectory_id);
640  const transform::Rigid3d old_global_to_new_global =
641  local_to_new_global * local_to_old_global.inverse();
642 
643  const NodeId last_optimized_node_id =
644  std::prev(node_data.EndOfTrajectory(trajectory_id))->id;
645  auto node_it = std::next(trajectory_nodes_.find(last_optimized_node_id));
646  for (; node_it != trajectory_nodes_.EndOfTrajectory(trajectory_id);
647  ++node_it) {
648  auto& mutable_trajectory_node = trajectory_nodes_.at(node_it->id);
649  mutable_trajectory_node.global_pose =
650  old_global_to_new_global * mutable_trajectory_node.global_pose;
651  }
652  }
653  for (const auto& landmark : optimization_problem_->landmark_data()) {
654  landmark_nodes_[landmark.first].global_landmark_pose = landmark.second;
655  }
656  global_submap_poses_ = submap_data;
657 
658  // Log the histograms for the pose residuals.
659  if (options_.log_residual_histograms()) {
661  }
662 }
663 
665  common::MutexLocker locker(&mutex_);
666  return trajectory_nodes_;
667 }
668 
670  const {
672  common::MutexLocker locker(&mutex_);
673  for (const auto& node_id_data : trajectory_nodes_) {
675  if (node_id_data.data.constant_data != nullptr) {
676  constant_pose_data = TrajectoryNodePose::ConstantPoseData{
677  node_id_data.data.constant_data->time,
678  node_id_data.data.constant_data->local_pose};
679  }
680  node_poses.Insert(
681  node_id_data.id,
682  TrajectoryNodePose{node_id_data.data.global_pose, constant_pose_data});
683  }
684  return node_poses;
685 }
686 
687 std::map<std::string, transform::Rigid3d> PoseGraph3D::GetLandmarkPoses()
688  const {
689  std::map<std::string, transform::Rigid3d> landmark_poses;
690  common::MutexLocker locker(&mutex_);
691  for (const auto& landmark : landmark_nodes_) {
692  // Landmark without value has not been optimized yet.
693  if (!landmark.second.global_landmark_pose.has_value()) continue;
694  landmark_poses[landmark.first] =
695  landmark.second.global_landmark_pose.value();
696  }
697  return landmark_poses;
698 }
699 
700 void PoseGraph3D::SetLandmarkPose(const std::string& landmark_id,
701  const transform::Rigid3d& global_pose) {
702  common::MutexLocker locker(&mutex_);
703  AddWorkItem([=]() REQUIRES(mutex_) {
704  landmark_nodes_[landmark_id].global_landmark_pose = global_pose;
705  });
706 }
707 
709  common::MutexLocker locker(&mutex_);
710  return optimization_problem_->imu_data();
711 }
712 
714  common::MutexLocker locker(&mutex_);
715  return optimization_problem_->odometry_data();
716 }
717 
720  common::MutexLocker locker(&mutex_);
721  return optimization_problem_->fixed_frame_pose_data();
722 }
723 
724 std::map<std::string /* landmark ID */, PoseGraphInterface::LandmarkNode>
726  common::MutexLocker locker(&mutex_);
727  return landmark_nodes_;
728 }
729 
730 std::map<int, PoseGraphInterface::TrajectoryData>
732  common::MutexLocker locker(&mutex_);
733  return optimization_problem_->trajectory_data();
734 }
735 
736 std::vector<PoseGraphInterface::Constraint> PoseGraph3D::constraints() const {
737  common::MutexLocker locker(&mutex_);
738  return constraints_;
739 }
740 
741 void PoseGraph3D::SetInitialTrajectoryPose(const int from_trajectory_id,
742  const int to_trajectory_id,
743  const transform::Rigid3d& pose,
744  const common::Time time) {
745  common::MutexLocker locker(&mutex_);
746  initial_trajectory_poses_[from_trajectory_id] =
747  InitialTrajectoryPose{to_trajectory_id, pose, time};
748 }
749 
751  const int trajectory_id, const common::Time time) const {
752  CHECK_GT(trajectory_nodes_.SizeOfTrajectoryOrZero(trajectory_id), 0);
753  const auto it = trajectory_nodes_.lower_bound(trajectory_id, time);
754  if (it == trajectory_nodes_.BeginOfTrajectory(trajectory_id)) {
755  return trajectory_nodes_.BeginOfTrajectory(trajectory_id)->data.global_pose;
756  }
757  if (it == trajectory_nodes_.EndOfTrajectory(trajectory_id)) {
758  return std::prev(trajectory_nodes_.EndOfTrajectory(trajectory_id))
759  ->data.global_pose;
760  }
761  return transform::Interpolate(
762  transform::TimestampedTransform{std::prev(it)->data.time(),
763  std::prev(it)->data.global_pose},
765  it->data.global_pose},
766  time)
767  .transform;
768 }
769 
771  const int trajectory_id) const {
772  common::MutexLocker locker(&mutex_);
773  return ComputeLocalToGlobalTransform(global_submap_poses_, trajectory_id);
774 }
775 
776 std::vector<std::vector<int>> PoseGraph3D::GetConnectedTrajectories() const {
778 }
779 
781  const SubmapId& submap_id) const {
782  common::MutexLocker locker(&mutex_);
783  return GetSubmapDataUnderLock(submap_id);
784 }
785 
788  common::MutexLocker locker(&mutex_);
789  return GetSubmapDataUnderLock();
790 }
791 
794  common::MutexLocker locker(&mutex_);
795  MapById<SubmapId, SubmapPose> submap_poses;
796  for (const auto& submap_id_data : submap_data_) {
797  auto submap_data = GetSubmapDataUnderLock(submap_id_data.id);
798  submap_poses.Insert(
799  submap_id_data.id,
800  PoseGraphInterface::SubmapPose{submap_data.submap->num_range_data(),
801  submap_data.pose});
802  }
803  return submap_poses;
804 }
805 
807  const MapById<SubmapId, optimization::SubmapSpec3D>& global_submap_poses,
808  const int trajectory_id) const {
809  auto begin_it = global_submap_poses.BeginOfTrajectory(trajectory_id);
810  auto end_it = global_submap_poses.EndOfTrajectory(trajectory_id);
811  if (begin_it == end_it) {
812  const auto it = initial_trajectory_poses_.find(trajectory_id);
813  if (it != initial_trajectory_poses_.end()) {
814  return GetInterpolatedGlobalTrajectoryPose(it->second.to_trajectory_id,
815  it->second.time) *
816  it->second.relative_pose;
817  } else {
819  }
820  }
821  const SubmapId last_optimized_submap_id = std::prev(end_it)->id;
822  // Accessing 'local_pose' in Submap is okay, since the member is const.
823  return global_submap_poses.at(last_optimized_submap_id).global_pose *
824  submap_data_.at(last_optimized_submap_id)
825  .submap->local_pose()
826  .inverse();
827 }
828 
830  const SubmapId& submap_id) const {
831  const auto it = submap_data_.find(submap_id);
832  if (it == submap_data_.end()) {
833  return {};
834  }
835  auto submap = it->data.submap;
836  if (global_submap_poses_.Contains(submap_id)) {
837  // We already have an optimized pose.
838  return {submap, global_submap_poses_.at(submap_id).global_pose};
839  }
840  // We have to extrapolate.
841  return {submap, ComputeLocalToGlobalTransform(global_submap_poses_,
842  submap_id.trajectory_id) *
843  submap->local_pose()};
844 }
845 
847  : parent_(parent) {}
848 
849 int PoseGraph3D::TrimmingHandle::num_submaps(const int trajectory_id) const {
850  const auto& submap_data = parent_->optimization_problem_->submap_data();
851  return submap_data.SizeOfTrajectoryOrZero(trajectory_id);
852 }
853 
855  int trajectory_id) const {
856  std::vector<SubmapId> submap_ids;
857  const auto& submap_data = parent_->optimization_problem_->submap_data();
858  for (const auto& it : submap_data.trajectory(trajectory_id)) {
859  submap_ids.push_back(it.id);
860  }
861  return submap_ids;
862 }
866  for (const auto& submap_id_data : parent_->submap_data_) {
867  if (submap_id_data.data.state != SubmapState::kFinished ||
868  !parent_->global_submap_poses_.Contains(submap_id_data.id)) {
869  continue;
870  }
871  submaps.Insert(
872  submap_id_data.id,
873  SubmapData{
874  submap_id_data.data.submap,
875  parent_->global_submap_poses_.at(submap_id_data.id).global_pose});
876  }
877  return submaps;
878 }
879 
882  return parent_->trajectory_nodes_;
883 }
884 
885 const std::vector<PoseGraphInterface::Constraint>&
887  return parent_->constraints_;
888 }
889 
890 bool PoseGraph3D::TrimmingHandle::IsFinished(const int trajectory_id) const {
891  return parent_->IsTrajectoryFinished(trajectory_id);
892 }
893 
895  const SubmapId& submap_id) {
896  // TODO(hrapp): We have to make sure that the trajectory has been finished
897  // if we want to delete the last submaps.
898  CHECK(parent_->submap_data_.at(submap_id).state == SubmapState::kFinished);
899 
900  // Compile all nodes that are still INTRA_SUBMAP constrained once the submap
901  // with 'submap_id' is gone.
902  std::set<NodeId> nodes_to_retain;
903  for (const Constraint& constraint : parent_->constraints_) {
904  if (constraint.tag == Constraint::Tag::INTRA_SUBMAP &&
905  constraint.submap_id != submap_id) {
906  nodes_to_retain.insert(constraint.node_id);
907  }
908  }
909  // Remove all 'constraints_' related to 'submap_id'.
910  std::set<NodeId> nodes_to_remove;
911  {
912  std::vector<Constraint> constraints;
913  for (const Constraint& constraint : parent_->constraints_) {
914  if (constraint.submap_id == submap_id) {
915  if (constraint.tag == Constraint::Tag::INTRA_SUBMAP &&
916  nodes_to_retain.count(constraint.node_id) == 0) {
917  // This node will no longer be INTRA_SUBMAP contrained and has to be
918  // removed.
919  nodes_to_remove.insert(constraint.node_id);
920  }
921  } else {
922  constraints.push_back(constraint);
923  }
924  }
925  parent_->constraints_ = std::move(constraints);
926  }
927  // Remove all 'constraints_' related to 'nodes_to_remove'.
928  {
929  std::vector<Constraint> constraints;
930  for (const Constraint& constraint : parent_->constraints_) {
931  if (nodes_to_remove.count(constraint.node_id) == 0) {
932  constraints.push_back(constraint);
933  }
934  }
935  parent_->constraints_ = std::move(constraints);
936  }
937 
938  // Mark the submap with 'submap_id' as trimmed and remove its data.
939  CHECK(parent_->submap_data_.at(submap_id).state == SubmapState::kFinished);
940  parent_->submap_data_.Trim(submap_id);
941  parent_->constraint_builder_.DeleteScanMatcher(submap_id);
942  parent_->optimization_problem_->TrimSubmap(submap_id);
943 
944  // Remove the 'nodes_to_remove' from the pose graph and the optimization
945  // problem.
946  for (const NodeId& node_id : nodes_to_remove) {
947  parent_->trajectory_nodes_.Trim(node_id);
948  parent_->optimization_problem_->TrimTrajectoryNode(node_id);
949  }
950 }
951 
955  for (const auto& submap_id_data : submap_data_) {
956  submaps.Insert(submap_id_data.id,
957  GetSubmapDataUnderLock(submap_id_data.id));
958  }
959  return submaps;
960 }
961 
965 }
966 
967 } // namespace mapping
968 } // namespace cartographer
MapById< SubmapId, SubmapData > GetSubmapDataUnderLock() const REQUIRES(mutex_)
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
Definition: pose_graph.cc:38
void WaitForAllComputations() EXCLUDES(mutex_)
void FinishTrajectory(int trajectory_id) override
std::vector< SubmapId > InitializeGlobalSubmapPoses(int trajectory_id, const common::Time time, const std::vector< std::shared_ptr< const Submap3D >> &insertion_submaps) REQUIRES(mutex_)
void SetGlobalSlamOptimizationCallback(PoseGraphInterface::GlobalSlamOptimizationCallback callback) override
void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_)
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
#define EXCLUDES(...)
Definition: mutex.h:53
void Connect(int trajectory_id_a, int trajectory_id_b, common::Time time)
enum cartographer::mapping::PoseGraphInterface::Constraint::Tag tag
void AddWorkItem(const std::function< void()> &work_item) REQUIRES(mutex_)
std::shared_ptr< const Data > constant_data
const DataType & at(const IdType &id) const
Definition: id.h:311
common::optional< transform::Rigid3d > fixed_frame_origin_in_map
transform::Rigid3d GetInterpolatedGlobalTrajectoryPose(int trajectory_id, const common::Time time) const REQUIRES(mutex_)
const proto::PoseGraphOptions options_
sensor::MapByTime< sensor::ImuData > GetImuData() const override EXCLUDES(mutex_)
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
std::vector< SubmapId > GetSubmapIds(int trajectory_id) const override
void Insert(const IdType &id, const DataType &data)
Definition: id.h:280
void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id, const transform::Rigid3d &pose, const common::Time time) override EXCLUDES(mutex_)
void AddTrimmer(std::unique_ptr< PoseGraphTrimmer > trimmer) override
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
void FreezeTrajectory(int trajectory_id) override
void AddLandmarkData(int trajectory_id, const sensor::LandmarkData &landmark_data) override EXCLUDES(mutex_)
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
void AddImuData(int trajectory_id, const sensor::ImuData &imu_data) override EXCLUDES(mutex_)
const Quaternion & rotation() const
void ComputeConstraintsForOldNodes(const SubmapId &submap_id) REQUIRES(mutex_)
ConstIterator EndOfTrajectory(const int trajectory_id) const
Definition: id.h:323
void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose) override EXCLUDES(mutex_)
static time_point time
TimestampedTransform Interpolate(const TimestampedTransform &start, const TimestampedTransform &end, const common::Time time)
const std::vector< Constraint > & GetConstraints() const override REQUIRES(parent_ -> mutex_)
Duration FromSeconds(const double seconds)
Definition: time.cc:24
common::Time LastConnectionTime(int trajectory_id_a, int trajectory_id_b)
OptimizationProblem3D optimization_problem_
std::string ToString(int buckets) const
proto::ProbabilityGridRangeDataInserterOptions2D options_
#define REQUIRES(...)
Definition: mutex.h:44
void AddSubmapFromProto(const transform::Rigid3d &global_submap_pose, const proto::Submap &submap) override
void AddNodeFromProto(const transform::Rigid3d &global_pose, const proto::Node &node) override
const Vector & translation() const
MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const override EXCLUDES(mutex_)
std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const override EXCLUDES(mutex_)
void HandleWorkQueue(const constraints::ConstraintBuilder3D::Result &result) REQUIRES(mutex_)
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const EXCLUDES(mutex_) override
bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_)
void ComputeConstraint(const NodeId &node_id, const SubmapId &submap_id) REQUIRES(mutex_)
std::map< int, TrajectoryData > GetTrajectoryData() const override
void UpdateTrajectoryConnectivity(const Constraint &constraint) REQUIRES(mutex_)
PoseGraph::SubmapData GetSubmapData(const SubmapId &submap_id) const EXCLUDES(mutex_) override
void MarkSubmapAsTrimmed(const SubmapId &submap_id) REQUIRES(parent_ -> mutex_) override
void ComputeConstraintsForNode(const NodeId &node_id, std::vector< std::shared_ptr< const Submap3D >> insertion_submaps, bool newly_finished_submap) REQUIRES(mutex_)
void AddSerializedConstraints(const std::vector< Constraint > &constraints) override
NodeId AddNode(std::shared_ptr< const TrajectoryNode::Data > constant_data, int trajectory_id, const std::vector< std::shared_ptr< const Submap3D >> &insertion_submaps) EXCLUDES(mutex_)
const MapById< NodeId, TrajectoryNode > & GetTrajectoryNodes() const override REQUIRES(parent_ -> mutex_)
sensor::MapByTime< sensor::FixedFramePoseData > GetFixedFramePoseData() const override EXCLUDES(mutex_)
void AddFixedFramePoseData(int trajectory_id, const sensor::FixedFramePoseData &fixed_frame_pose_data) override EXCLUDES(mutex_)
void AddNodeToSubmap(const NodeId &node_id, const SubmapId &submap_id) override
void AddOdometryData(int trajectory_id, const sensor::OdometryData &odometry_data) override EXCLUDES(mutex_)
void DispatchOptimization() REQUIRES(mutex_)
MapById< SubmapId, SubmapData > GetAllSubmapData() const EXCLUDES(mutex_) override
std::unique_ptr< optimization::OptimizationProblem3D > optimization_problem_
void LogResidualHistograms() const REQUIRES(mutex_)
MapById< SubmapId, SubmapData > GetOptimizedSubmapData() const override REQUIRES(parent_ -> mutex_)
sensor::MapByTime< sensor::OdometryData > GetOdometryData() const override EXCLUDES(mutex_)
FloatType GetAngle(const Rigid3< FloatType > &transform)
Definition: transform.h:34
PoseGraph3D(const proto::PoseGraphOptions &options, std::unique_ptr< optimization::OptimizationProblem3D > optimization_problem, common::ThreadPool *thread_pool)
void RunOptimization() EXCLUDES(mutex_)
bool IsFinished(int trajectory_id) const override REQUIRES(parent_ -> mutex_)
std::vector< Constraint > constraints() const override EXCLUDES(mutex_)
transform::Rigid3d ComputeLocalToGlobalTransform(const MapById< SubmapId, optimization::SubmapSpec3D > &global_submap_poses, int trajectory_id) const REQUIRES(mutex_)
T NormalizeAngleDifference(T difference)
Definition: math.h:62
std::map< std::string, PoseGraph::LandmarkNode > GetLandmarkNodes() const override EXCLUDES(mutex_)
transform::Rigid3d pose
int num_submaps(int trajectory_id) const override
std::vector< std::vector< int > > GetConnectedTrajectories() const override
Mutex::Locker MutexLocker
Definition: mutex.h:95
ConstIterator BeginOfTrajectory(const int trajectory_id) const
Definition: id.h:320
bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_)
MapById< NodeId, TrajectoryNodePose > GetTrajectoryNodePoses() const override EXCLUDES(mutex_)
GlobalSlamOptimizationCallback global_slam_optimization_callback_
MapById< SubmapId, SubmapPose > GetAllSubmapPoses() const EXCLUDES(mutex_) override
common::Time GetLatestNodeTime(const NodeId &node_id, const SubmapId &submap_id) const REQUIRES(mutex_)
void SetTrajectoryDataFromProto(const proto::TrajectoryData &data) override
TrajectoryConnectivityState trajectory_connectivity_state_


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