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


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