pose_graph_3d.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/mapping/internal/3d/pose_graph_3d.h"
00018 
00019 #include <algorithm>
00020 #include <cmath>
00021 #include <cstdio>
00022 #include <functional>
00023 #include <iomanip>
00024 #include <iostream>
00025 #include <limits>
00026 #include <memory>
00027 #include <sstream>
00028 #include <string>
00029 
00030 #include "Eigen/Eigenvalues"
00031 #include "absl/memory/memory.h"
00032 #include "cartographer/common/math.h"
00033 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h"
00034 #include "cartographer/sensor/compressed_point_cloud.h"
00035 #include "cartographer/sensor/internal/voxel_filter.h"
00036 #include "cartographer/transform/transform.h"
00037 #include "glog/logging.h"
00038 
00039 namespace cartographer {
00040 namespace mapping {
00041 
00042 static auto* kWorkQueueDelayMetric = metrics::Gauge::Null();
00043 static auto* kConstraintsSameTrajectoryMetric = metrics::Gauge::Null();
00044 static auto* kConstraintsDifferentTrajectoryMetric = metrics::Gauge::Null();
00045 static auto* kActiveSubmapsMetric = metrics::Gauge::Null();
00046 static auto* kFrozenSubmapsMetric = metrics::Gauge::Null();
00047 static auto* kDeletedSubmapsMetric = metrics::Gauge::Null();
00048 
00049 PoseGraph3D::PoseGraph3D(
00050     const proto::PoseGraphOptions& options,
00051     std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem,
00052     common::ThreadPool* thread_pool)
00053     : options_(options),
00054       optimization_problem_(std::move(optimization_problem)),
00055       constraint_builder_(options_.constraint_builder_options(), thread_pool),
00056       thread_pool_(thread_pool) {}
00057 
00058 PoseGraph3D::~PoseGraph3D() {
00059   WaitForAllComputations();
00060   absl::MutexLock locker(&work_queue_mutex_);
00061   CHECK(work_queue_ == nullptr);
00062 }
00063 
00064 std::vector<SubmapId> PoseGraph3D::InitializeGlobalSubmapPoses(
00065     const int trajectory_id, const common::Time time,
00066     const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps) {
00067   CHECK(!insertion_submaps.empty());
00068   const auto& submap_data = optimization_problem_->submap_data();
00069   if (insertion_submaps.size() == 1) {
00070     // If we don't already have an entry for the first submap, add one.
00071     if (submap_data.SizeOfTrajectoryOrZero(trajectory_id) == 0) {
00072       if (data_.initial_trajectory_poses.count(trajectory_id) > 0) {
00073         data_.trajectory_connectivity_state.Connect(
00074             trajectory_id,
00075             data_.initial_trajectory_poses.at(trajectory_id).to_trajectory_id,
00076             time);
00077       }
00078       optimization_problem_->AddSubmap(
00079           trajectory_id, ComputeLocalToGlobalTransform(
00080                              data_.global_submap_poses_3d, trajectory_id) *
00081                              insertion_submaps[0]->local_pose());
00082     }
00083     CHECK_EQ(1, submap_data.SizeOfTrajectoryOrZero(trajectory_id));
00084     const SubmapId submap_id{trajectory_id, 0};
00085     CHECK(data_.submap_data.at(submap_id).submap == insertion_submaps.front());
00086     return {submap_id};
00087   }
00088   CHECK_EQ(2, insertion_submaps.size());
00089   const auto end_it = submap_data.EndOfTrajectory(trajectory_id);
00090   CHECK(submap_data.BeginOfTrajectory(trajectory_id) != end_it);
00091   const SubmapId last_submap_id = std::prev(end_it)->id;
00092   if (data_.submap_data.at(last_submap_id).submap ==
00093       insertion_submaps.front()) {
00094     // In this case, 'last_submap_id' is the ID of 'insertions_submaps.front()'
00095     // and 'insertions_submaps.back()' is new.
00096     const auto& first_submap_pose = submap_data.at(last_submap_id).global_pose;
00097     optimization_problem_->AddSubmap(
00098         trajectory_id, first_submap_pose *
00099                            insertion_submaps[0]->local_pose().inverse() *
00100                            insertion_submaps[1]->local_pose());
00101     return {last_submap_id,
00102             SubmapId{trajectory_id, last_submap_id.submap_index + 1}};
00103   }
00104   CHECK(data_.submap_data.at(last_submap_id).submap ==
00105         insertion_submaps.back());
00106   const SubmapId front_submap_id{trajectory_id,
00107                                  last_submap_id.submap_index - 1};
00108   CHECK(data_.submap_data.at(front_submap_id).submap ==
00109         insertion_submaps.front());
00110   return {front_submap_id, last_submap_id};
00111 }
00112 
00113 NodeId PoseGraph3D::AppendNode(
00114     std::shared_ptr<const TrajectoryNode::Data> constant_data,
00115     const int trajectory_id,
00116     const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps,
00117     const transform::Rigid3d& optimized_pose) {
00118   absl::MutexLock locker(&mutex_);
00119   AddTrajectoryIfNeeded(trajectory_id);
00120   if (!CanAddWorkItemModifying(trajectory_id)) {
00121     LOG(WARNING) << "AddNode was called for finished or deleted trajectory.";
00122   }
00123   const NodeId node_id = data_.trajectory_nodes.Append(
00124       trajectory_id, TrajectoryNode{constant_data, optimized_pose});
00125   ++data_.num_trajectory_nodes;
00126   // Test if the 'insertion_submap.back()' is one we never saw before.
00127   if (data_.submap_data.SizeOfTrajectoryOrZero(trajectory_id) == 0 ||
00128       std::prev(data_.submap_data.EndOfTrajectory(trajectory_id))
00129               ->data.submap != insertion_submaps.back()) {
00130     // We grow 'data_.submap_data' as needed. This code assumes that the first
00131     // time we see a new submap is as 'insertion_submaps.back()'.
00132     const SubmapId submap_id =
00133         data_.submap_data.Append(trajectory_id, InternalSubmapData());
00134     data_.submap_data.at(submap_id).submap = insertion_submaps.back();
00135     LOG(INFO) << "Inserted submap " << submap_id << ".";
00136     kActiveSubmapsMetric->Increment();
00137   }
00138   return node_id;
00139 }
00140 
00141 NodeId PoseGraph3D::AddNode(
00142     std::shared_ptr<const TrajectoryNode::Data> constant_data,
00143     const int trajectory_id,
00144     const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps) {
00145   const transform::Rigid3d optimized_pose(
00146       GetLocalToGlobalTransform(trajectory_id) * constant_data->local_pose);
00147 
00148   const NodeId node_id = AppendNode(constant_data, trajectory_id,
00149                                     insertion_submaps, optimized_pose);
00150   // We have to check this here, because it might have changed by the time we
00151   // execute the lambda.
00152   const bool newly_finished_submap =
00153       insertion_submaps.front()->insertion_finished();
00154   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00155     return ComputeConstraintsForNode(node_id, insertion_submaps,
00156                                      newly_finished_submap);
00157   });
00158   return node_id;
00159 }
00160 
00161 void PoseGraph3D::AddWorkItem(
00162     const std::function<WorkItem::Result()>& work_item) {
00163   absl::MutexLock locker(&work_queue_mutex_);
00164   if (work_queue_ == nullptr) {
00165     work_queue_ = absl::make_unique<WorkQueue>();
00166     auto task = absl::make_unique<common::Task>();
00167     task->SetWorkItem([this]() { DrainWorkQueue(); });
00168     thread_pool_->Schedule(std::move(task));
00169   }
00170   const auto now = std::chrono::steady_clock::now();
00171   work_queue_->push_back({now, work_item});
00172   kWorkQueueDelayMetric->Set(
00173       std::chrono::duration_cast<std::chrono::duration<double>>(
00174           now - work_queue_->front().time)
00175           .count());
00176 }
00177 
00178 void PoseGraph3D::AddTrajectoryIfNeeded(const int trajectory_id) {
00179   data_.trajectories_state[trajectory_id];
00180   CHECK(data_.trajectories_state.at(trajectory_id).state !=
00181         TrajectoryState::FINISHED);
00182   CHECK(data_.trajectories_state.at(trajectory_id).state !=
00183         TrajectoryState::DELETED);
00184   CHECK(data_.trajectories_state.at(trajectory_id).deletion_state ==
00185         InternalTrajectoryState::DeletionState::NORMAL);
00186   data_.trajectory_connectivity_state.Add(trajectory_id);
00187   // Make sure we have a sampler for this trajectory.
00188   if (!global_localization_samplers_[trajectory_id]) {
00189     global_localization_samplers_[trajectory_id] =
00190         absl::make_unique<common::FixedRatioSampler>(
00191             options_.global_sampling_ratio());
00192   }
00193 }
00194 
00195 void PoseGraph3D::AddImuData(const int trajectory_id,
00196                              const sensor::ImuData& imu_data) {
00197   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00198     absl::MutexLock locker(&mutex_);
00199     if (CanAddWorkItemModifying(trajectory_id)) {
00200       optimization_problem_->AddImuData(trajectory_id, imu_data);
00201     }
00202     return WorkItem::Result::kDoNotRunOptimization;
00203   });
00204 }
00205 
00206 void PoseGraph3D::AddOdometryData(const int trajectory_id,
00207                                   const sensor::OdometryData& odometry_data) {
00208   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00209     absl::MutexLock locker(&mutex_);
00210     if (CanAddWorkItemModifying(trajectory_id)) {
00211       optimization_problem_->AddOdometryData(trajectory_id, odometry_data);
00212     }
00213     return WorkItem::Result::kDoNotRunOptimization;
00214   });
00215 }
00216 
00217 void PoseGraph3D::AddFixedFramePoseData(
00218     const int trajectory_id,
00219     const sensor::FixedFramePoseData& fixed_frame_pose_data) {
00220   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00221     absl::MutexLock locker(&mutex_);
00222     if (CanAddWorkItemModifying(trajectory_id)) {
00223       optimization_problem_->AddFixedFramePoseData(trajectory_id,
00224                                                    fixed_frame_pose_data);
00225     }
00226     return WorkItem::Result::kDoNotRunOptimization;
00227   });
00228 }
00229 
00230 void PoseGraph3D::AddLandmarkData(int trajectory_id,
00231                                   const sensor::LandmarkData& landmark_data) {
00232   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00233     absl::MutexLock locker(&mutex_);
00234     if (CanAddWorkItemModifying(trajectory_id)) {
00235       for (const auto& observation : landmark_data.landmark_observations) {
00236         data_.landmark_nodes[observation.id].landmark_observations.emplace_back(
00237             PoseGraphInterface::LandmarkNode::LandmarkObservation{
00238                 trajectory_id, landmark_data.time,
00239                 observation.landmark_to_tracking_transform,
00240                 observation.translation_weight, observation.rotation_weight});
00241       }
00242     }
00243     return WorkItem::Result::kDoNotRunOptimization;
00244   });
00245 }
00246 
00247 void PoseGraph3D::ComputeConstraint(const NodeId& node_id,
00248                                     const SubmapId& submap_id) {
00249   const transform::Rigid3d global_node_pose =
00250       optimization_problem_->node_data().at(node_id).global_pose;
00251 
00252   const transform::Rigid3d global_submap_pose =
00253       optimization_problem_->submap_data().at(submap_id).global_pose;
00254 
00255   bool maybe_add_local_constraint = false;
00256   bool maybe_add_global_constraint = false;
00257   const TrajectoryNode::Data* constant_data;
00258   const Submap3D* submap;
00259   {
00260     absl::MutexLock locker(&mutex_);
00261     CHECK(data_.submap_data.at(submap_id).state == SubmapState::kFinished);
00262     if (!data_.submap_data.at(submap_id).submap->insertion_finished()) {
00263       // Uplink server only receives grids when they are finished, so skip
00264       // constraint search before that.
00265       return;
00266     }
00267 
00268     const common::Time node_time = GetLatestNodeTime(node_id, submap_id);
00269     const common::Time last_connection_time =
00270         data_.trajectory_connectivity_state.LastConnectionTime(
00271             node_id.trajectory_id, submap_id.trajectory_id);
00272     if (node_id.trajectory_id == submap_id.trajectory_id ||
00273         node_time <
00274             last_connection_time +
00275                 common::FromSeconds(
00276                     options_.global_constraint_search_after_n_seconds())) {
00277       // If the node and the submap belong to the same trajectory or if there
00278       // has been a recent global constraint that ties that node's trajectory to
00279       // the submap's trajectory, it suffices to do a match constrained to a
00280       // local search window.
00281       maybe_add_local_constraint = true;
00282     } else if (global_localization_samplers_[node_id.trajectory_id]->Pulse()) {
00283       // In this situation, 'global_node_pose' and 'global_submap_pose' have
00284       // orientations agreeing on gravity. Their relationship regarding yaw is
00285       // arbitrary. Finding the correct yaw component will be handled by the
00286       // matching procedure in the FastCorrelativeScanMatcher, and the given yaw
00287       // is essentially ignored.
00288       maybe_add_global_constraint = true;
00289     }
00290     constant_data = data_.trajectory_nodes.at(node_id).constant_data.get();
00291     submap = static_cast<const Submap3D*>(
00292         data_.submap_data.at(submap_id).submap.get());
00293   }
00294 
00295   if (maybe_add_local_constraint) {
00296     constraint_builder_.MaybeAddConstraint(submap_id, submap, node_id,
00297                                            constant_data, global_node_pose,
00298                                            global_submap_pose);
00299   } else if (maybe_add_global_constraint) {
00300     constraint_builder_.MaybeAddGlobalConstraint(
00301         submap_id, submap, node_id, constant_data, global_node_pose.rotation(),
00302         global_submap_pose.rotation());
00303   }
00304 }
00305 
00306 WorkItem::Result PoseGraph3D::ComputeConstraintsForNode(
00307     const NodeId& node_id,
00308     std::vector<std::shared_ptr<const Submap3D>> insertion_submaps,
00309     const bool newly_finished_submap) {
00310   std::vector<SubmapId> submap_ids;
00311   std::vector<SubmapId> finished_submap_ids;
00312   std::set<NodeId> newly_finished_submap_node_ids;
00313   {
00314     absl::MutexLock locker(&mutex_);
00315     const auto& constant_data =
00316         data_.trajectory_nodes.at(node_id).constant_data;
00317     submap_ids = InitializeGlobalSubmapPoses(
00318         node_id.trajectory_id, constant_data->time, insertion_submaps);
00319     CHECK_EQ(submap_ids.size(), insertion_submaps.size());
00320     const SubmapId matching_id = submap_ids.front();
00321     const transform::Rigid3d& local_pose = constant_data->local_pose;
00322     const transform::Rigid3d global_pose =
00323         optimization_problem_->submap_data().at(matching_id).global_pose *
00324         insertion_submaps.front()->local_pose().inverse() * local_pose;
00325     optimization_problem_->AddTrajectoryNode(
00326         matching_id.trajectory_id,
00327         optimization::NodeSpec3D{constant_data->time, local_pose, global_pose});
00328     for (size_t i = 0; i < insertion_submaps.size(); ++i) {
00329       const SubmapId submap_id = submap_ids[i];
00330       // Even if this was the last node added to 'submap_id', the submap will
00331       // only be marked as finished in 'data_.submap_data' further below.
00332       CHECK(data_.submap_data.at(submap_id).state ==
00333             SubmapState::kNoConstraintSearch);
00334       data_.submap_data.at(submap_id).node_ids.emplace(node_id);
00335       const transform::Rigid3d constraint_transform =
00336           insertion_submaps[i]->local_pose().inverse() * local_pose;
00337       data_.constraints.push_back(Constraint{
00338           submap_id,
00339           node_id,
00340           {constraint_transform, options_.matcher_translation_weight(),
00341            options_.matcher_rotation_weight()},
00342           Constraint::INTRA_SUBMAP});
00343     }
00344     // TODO(gaschler): Consider not searching for constraints against
00345     // trajectories scheduled for deletion.
00346     // TODO(danielsievers): Add a member variable and avoid having to copy
00347     // them out here.
00348     for (const auto& submap_id_data : data_.submap_data) {
00349       if (submap_id_data.data.state == SubmapState::kFinished) {
00350         CHECK_EQ(submap_id_data.data.node_ids.count(node_id), 0);
00351         finished_submap_ids.emplace_back(submap_id_data.id);
00352       }
00353     }
00354     if (newly_finished_submap) {
00355       const SubmapId newly_finished_submap_id = submap_ids.front();
00356       InternalSubmapData& finished_submap_data =
00357           data_.submap_data.at(newly_finished_submap_id);
00358       CHECK(finished_submap_data.state == SubmapState::kNoConstraintSearch);
00359       finished_submap_data.state = SubmapState::kFinished;
00360       newly_finished_submap_node_ids = finished_submap_data.node_ids;
00361     }
00362   }
00363 
00364   for (const auto& submap_id : finished_submap_ids) {
00365     ComputeConstraint(node_id, submap_id);
00366   }
00367 
00368   if (newly_finished_submap) {
00369     const SubmapId newly_finished_submap_id = submap_ids.front();
00370     // We have a new completed submap, so we look into adding constraints for
00371     // old nodes.
00372     for (const auto& node_id_data : optimization_problem_->node_data()) {
00373       const NodeId& node_id = node_id_data.id;
00374       if (newly_finished_submap_node_ids.count(node_id) == 0) {
00375         ComputeConstraint(node_id, newly_finished_submap_id);
00376       }
00377     }
00378   }
00379   constraint_builder_.NotifyEndOfNode();
00380   absl::MutexLock locker(&mutex_);
00381   ++num_nodes_since_last_loop_closure_;
00382   if (options_.optimize_every_n_nodes() > 0 &&
00383       num_nodes_since_last_loop_closure_ > options_.optimize_every_n_nodes()) {
00384     return WorkItem::Result::kRunOptimization;
00385   }
00386   return WorkItem::Result::kDoNotRunOptimization;
00387 }
00388 
00389 common::Time PoseGraph3D::GetLatestNodeTime(const NodeId& node_id,
00390                                             const SubmapId& submap_id) const {
00391   common::Time time = data_.trajectory_nodes.at(node_id).constant_data->time;
00392   const InternalSubmapData& submap_data = data_.submap_data.at(submap_id);
00393   if (!submap_data.node_ids.empty()) {
00394     const NodeId last_submap_node_id =
00395         *data_.submap_data.at(submap_id).node_ids.rbegin();
00396     time = std::max(
00397         time,
00398         data_.trajectory_nodes.at(last_submap_node_id).constant_data->time);
00399   }
00400   return time;
00401 }
00402 
00403 void PoseGraph3D::UpdateTrajectoryConnectivity(const Constraint& constraint) {
00404   CHECK_EQ(constraint.tag, PoseGraphInterface::Constraint::INTER_SUBMAP);
00405   const common::Time time =
00406       GetLatestNodeTime(constraint.node_id, constraint.submap_id);
00407   data_.trajectory_connectivity_state.Connect(
00408       constraint.node_id.trajectory_id, constraint.submap_id.trajectory_id,
00409       time);
00410 }
00411 
00412 void PoseGraph3D::DeleteTrajectoriesIfNeeded() {
00413   TrimmingHandle trimming_handle(this);
00414   for (auto& it : data_.trajectories_state) {
00415     if (it.second.deletion_state ==
00416         InternalTrajectoryState::DeletionState::WAIT_FOR_DELETION) {
00417       // TODO(gaschler): Consider directly deleting from data_, which may be
00418       // more complete.
00419       auto submap_ids = trimming_handle.GetSubmapIds(it.first);
00420       for (auto& submap_id : submap_ids) {
00421         trimming_handle.TrimSubmap(submap_id);
00422       }
00423       it.second.state = TrajectoryState::DELETED;
00424       it.second.deletion_state = InternalTrajectoryState::DeletionState::NORMAL;
00425     }
00426   }
00427 }
00428 
00429 void PoseGraph3D::HandleWorkQueue(
00430     const constraints::ConstraintBuilder3D::Result& result) {
00431   {
00432     absl::MutexLock locker(&mutex_);
00433     data_.constraints.insert(data_.constraints.end(), result.begin(),
00434                              result.end());
00435   }
00436   RunOptimization();
00437 
00438   if (global_slam_optimization_callback_) {
00439     std::map<int, NodeId> trajectory_id_to_last_optimized_node_id;
00440     std::map<int, SubmapId> trajectory_id_to_last_optimized_submap_id;
00441     {
00442       absl::MutexLock locker(&mutex_);
00443       const auto& submap_data = optimization_problem_->submap_data();
00444       const auto& node_data = optimization_problem_->node_data();
00445       for (const int trajectory_id : node_data.trajectory_ids()) {
00446         if (node_data.SizeOfTrajectoryOrZero(trajectory_id) == 0 ||
00447             submap_data.SizeOfTrajectoryOrZero(trajectory_id) == 0) {
00448           continue;
00449         }
00450         trajectory_id_to_last_optimized_node_id.emplace(
00451             trajectory_id,
00452             std::prev(node_data.EndOfTrajectory(trajectory_id))->id);
00453         trajectory_id_to_last_optimized_submap_id.emplace(
00454             trajectory_id,
00455             std::prev(submap_data.EndOfTrajectory(trajectory_id))->id);
00456       }
00457     }
00458     global_slam_optimization_callback_(
00459         trajectory_id_to_last_optimized_submap_id,
00460         trajectory_id_to_last_optimized_node_id);
00461   }
00462 
00463   {
00464     absl::MutexLock locker(&mutex_);
00465     for (const Constraint& constraint : result) {
00466       UpdateTrajectoryConnectivity(constraint);
00467     }
00468     DeleteTrajectoriesIfNeeded();
00469     TrimmingHandle trimming_handle(this);
00470     for (auto& trimmer : trimmers_) {
00471       trimmer->Trim(&trimming_handle);
00472     }
00473     trimmers_.erase(
00474         std::remove_if(trimmers_.begin(), trimmers_.end(),
00475                        [](std::unique_ptr<PoseGraphTrimmer>& trimmer) {
00476                          return trimmer->IsFinished();
00477                        }),
00478         trimmers_.end());
00479 
00480     num_nodes_since_last_loop_closure_ = 0;
00481 
00482     // Update the gauges that count the current number of constraints.
00483     double inter_constraints_same_trajectory = 0;
00484     double inter_constraints_different_trajectory = 0;
00485     for (const auto& constraint : data_.constraints) {
00486       if (constraint.tag ==
00487           cartographer::mapping::PoseGraph::Constraint::INTRA_SUBMAP) {
00488         continue;
00489       }
00490       if (constraint.node_id.trajectory_id ==
00491           constraint.submap_id.trajectory_id) {
00492         ++inter_constraints_same_trajectory;
00493       } else {
00494         ++inter_constraints_different_trajectory;
00495       }
00496     }
00497     kConstraintsSameTrajectoryMetric->Set(inter_constraints_same_trajectory);
00498     kConstraintsDifferentTrajectoryMetric->Set(
00499         inter_constraints_different_trajectory);
00500   }
00501 
00502   DrainWorkQueue();
00503 }
00504 
00505 void PoseGraph3D::DrainWorkQueue() {
00506   bool process_work_queue = true;
00507   size_t work_queue_size;
00508   while (process_work_queue) {
00509     std::function<WorkItem::Result()> work_item;
00510     {
00511       absl::MutexLock locker(&work_queue_mutex_);
00512       if (work_queue_->empty()) {
00513         work_queue_.reset();
00514         return;
00515       }
00516       work_item = work_queue_->front().task;
00517       work_queue_->pop_front();
00518       work_queue_size = work_queue_->size();
00519     }
00520     process_work_queue = work_item() == WorkItem::Result::kDoNotRunOptimization;
00521   }
00522   LOG(INFO) << "Remaining work items in queue: " << work_queue_size;
00523   // We have to optimize again.
00524   constraint_builder_.WhenDone(
00525       [this](const constraints::ConstraintBuilder3D::Result& result) {
00526         HandleWorkQueue(result);
00527       });
00528 }
00529 
00530 void PoseGraph3D::WaitForAllComputations() {
00531   int num_trajectory_nodes;
00532   {
00533     absl::MutexLock locker(&mutex_);
00534     num_trajectory_nodes = data_.num_trajectory_nodes;
00535   }
00536 
00537   const int num_finished_nodes_at_start =
00538       constraint_builder_.GetNumFinishedNodes();
00539 
00540   auto report_progress = [this, num_trajectory_nodes,
00541                           num_finished_nodes_at_start]() {
00542     // Log progress on nodes only when we are actually processing nodes.
00543     if (num_trajectory_nodes != num_finished_nodes_at_start) {
00544       std::ostringstream progress_info;
00545       progress_info << "Optimizing: " << std::fixed << std::setprecision(1)
00546                     << 100. *
00547                            (constraint_builder_.GetNumFinishedNodes() -
00548                             num_finished_nodes_at_start) /
00549                            (num_trajectory_nodes - num_finished_nodes_at_start)
00550                     << "%...";
00551       std::cout << "\r\x1b[K" << progress_info.str() << std::flush;
00552     }
00553   };
00554 
00555   // First wait for the work queue to drain so that it's safe to schedule
00556   // a WhenDone() callback.
00557   {
00558     const auto predicate = [this]()
00559                                EXCLUSIVE_LOCKS_REQUIRED(work_queue_mutex_) {
00560                                  return work_queue_ == nullptr;
00561                                };
00562     absl::MutexLock locker(&work_queue_mutex_);
00563     while (!work_queue_mutex_.AwaitWithTimeout(
00564         absl::Condition(&predicate),
00565         absl::FromChrono(common::FromSeconds(1.)))) {
00566       report_progress();
00567     }
00568   }
00569 
00570   // Now wait for any pending constraint computations to finish.
00571   absl::MutexLock locker(&mutex_);
00572   bool notification = false;
00573   constraint_builder_.WhenDone(
00574       [this,
00575        &notification](const constraints::ConstraintBuilder3D::Result& result)
00576           LOCKS_EXCLUDED(mutex_) {
00577             absl::MutexLock locker(&mutex_);
00578             data_.constraints.insert(data_.constraints.end(), result.begin(),
00579                                      result.end());
00580             notification = true;
00581           });
00582   const auto predicate = [&notification]() EXCLUSIVE_LOCKS_REQUIRED(mutex_) {
00583     return notification;
00584   };
00585   while (!mutex_.AwaitWithTimeout(absl::Condition(&predicate),
00586                                   absl::FromChrono(common::FromSeconds(1.)))) {
00587     report_progress();
00588   }
00589   CHECK_EQ(constraint_builder_.GetNumFinishedNodes(), num_trajectory_nodes);
00590   std::cout << "\r\x1b[KOptimizing: Done.     " << std::endl;
00591 }
00592 
00593 void PoseGraph3D::DeleteTrajectory(const int trajectory_id) {
00594   {
00595     absl::MutexLock locker(&mutex_);
00596     auto it = data_.trajectories_state.find(trajectory_id);
00597     if (it == data_.trajectories_state.end()) {
00598       LOG(WARNING) << "Skipping request to delete non-existing trajectory_id: "
00599                    << trajectory_id;
00600       return;
00601     }
00602     it->second.deletion_state =
00603         InternalTrajectoryState::DeletionState::SCHEDULED_FOR_DELETION;
00604   }
00605   AddWorkItem([this, trajectory_id]() LOCKS_EXCLUDED(mutex_) {
00606     absl::MutexLock locker(&mutex_);
00607     CHECK(data_.trajectories_state.at(trajectory_id).state !=
00608           TrajectoryState::ACTIVE);
00609     CHECK(data_.trajectories_state.at(trajectory_id).state !=
00610           TrajectoryState::DELETED);
00611     CHECK(data_.trajectories_state.at(trajectory_id).deletion_state ==
00612           InternalTrajectoryState::DeletionState::SCHEDULED_FOR_DELETION);
00613     data_.trajectories_state.at(trajectory_id).deletion_state =
00614         InternalTrajectoryState::DeletionState::WAIT_FOR_DELETION;
00615     return WorkItem::Result::kDoNotRunOptimization;
00616   });
00617 }
00618 
00619 void PoseGraph3D::FinishTrajectory(const int trajectory_id) {
00620   AddWorkItem([this, trajectory_id]() LOCKS_EXCLUDED(mutex_) {
00621     absl::MutexLock locker(&mutex_);
00622     CHECK(!IsTrajectoryFinished(trajectory_id));
00623     data_.trajectories_state[trajectory_id].state = TrajectoryState::FINISHED;
00624 
00625     for (const auto& submap : data_.submap_data.trajectory(trajectory_id)) {
00626       data_.submap_data.at(submap.id).state = SubmapState::kFinished;
00627     }
00628     return WorkItem::Result::kRunOptimization;
00629   });
00630 }
00631 
00632 bool PoseGraph3D::IsTrajectoryFinished(const int trajectory_id) const {
00633   return data_.trajectories_state.count(trajectory_id) != 0 &&
00634          data_.trajectories_state.at(trajectory_id).state ==
00635              TrajectoryState::FINISHED;
00636 }
00637 
00638 void PoseGraph3D::FreezeTrajectory(const int trajectory_id) {
00639   {
00640     absl::MutexLock locker(&mutex_);
00641     data_.trajectory_connectivity_state.Add(trajectory_id);
00642   }
00643   AddWorkItem([this, trajectory_id]() LOCKS_EXCLUDED(mutex_) {
00644     absl::MutexLock locker(&mutex_);
00645     CHECK(!IsTrajectoryFrozen(trajectory_id));
00646     data_.trajectories_state[trajectory_id].state = TrajectoryState::FROZEN;
00647     return WorkItem::Result::kDoNotRunOptimization;
00648   });
00649 }
00650 
00651 bool PoseGraph3D::IsTrajectoryFrozen(const int trajectory_id) const {
00652   return data_.trajectories_state.count(trajectory_id) != 0 &&
00653          data_.trajectories_state.at(trajectory_id).state ==
00654              TrajectoryState::FROZEN;
00655 }
00656 
00657 void PoseGraph3D::AddSubmapFromProto(
00658     const transform::Rigid3d& global_submap_pose, const proto::Submap& submap) {
00659   if (!submap.has_submap_3d()) {
00660     return;
00661   }
00662 
00663   const SubmapId submap_id = {submap.submap_id().trajectory_id(),
00664                               submap.submap_id().submap_index()};
00665   std::shared_ptr<const Submap3D> submap_ptr =
00666       std::make_shared<const Submap3D>(submap.submap_3d());
00667 
00668   {
00669     absl::MutexLock locker(&mutex_);
00670     AddTrajectoryIfNeeded(submap_id.trajectory_id);
00671     if (!CanAddWorkItemModifying(submap_id.trajectory_id)) return;
00672     data_.submap_data.Insert(submap_id, InternalSubmapData());
00673     data_.submap_data.at(submap_id).submap = submap_ptr;
00674     // Immediately show the submap at the 'global_submap_pose'.
00675     data_.global_submap_poses_3d.Insert(
00676         submap_id, optimization::SubmapSpec3D{global_submap_pose});
00677   }
00678 
00679   // TODO(MichaelGrupp): MapBuilder does freezing before deserializing submaps,
00680   // so this should be fine.
00681   if (IsTrajectoryFrozen(submap_id.trajectory_id)) {
00682     kFrozenSubmapsMetric->Increment();
00683   } else {
00684     kActiveSubmapsMetric->Increment();
00685   }
00686 
00687   AddWorkItem([this, submap_id, global_submap_pose]() LOCKS_EXCLUDED(mutex_) {
00688     absl::MutexLock locker(&mutex_);
00689     data_.submap_data.at(submap_id).state = SubmapState::kFinished;
00690     optimization_problem_->InsertSubmap(submap_id, global_submap_pose);
00691     return WorkItem::Result::kDoNotRunOptimization;
00692   });
00693 }
00694 
00695 void PoseGraph3D::AddNodeFromProto(const transform::Rigid3d& global_pose,
00696                                    const proto::Node& node) {
00697   const NodeId node_id = {node.node_id().trajectory_id(),
00698                           node.node_id().node_index()};
00699   std::shared_ptr<const TrajectoryNode::Data> constant_data =
00700       std::make_shared<const TrajectoryNode::Data>(FromProto(node.node_data()));
00701 
00702   {
00703     absl::MutexLock locker(&mutex_);
00704     AddTrajectoryIfNeeded(node_id.trajectory_id);
00705     if (!CanAddWorkItemModifying(node_id.trajectory_id)) return;
00706     data_.trajectory_nodes.Insert(node_id,
00707                                   TrajectoryNode{constant_data, global_pose});
00708   }
00709 
00710   AddWorkItem([this, node_id, global_pose]() LOCKS_EXCLUDED(mutex_) {
00711     absl::MutexLock locker(&mutex_);
00712     const auto& constant_data =
00713         data_.trajectory_nodes.at(node_id).constant_data;
00714     optimization_problem_->InsertTrajectoryNode(
00715         node_id,
00716         optimization::NodeSpec3D{constant_data->time, constant_data->local_pose,
00717                                  global_pose});
00718     return WorkItem::Result::kDoNotRunOptimization;
00719   });
00720 }
00721 
00722 void PoseGraph3D::SetTrajectoryDataFromProto(
00723     const proto::TrajectoryData& data) {
00724   TrajectoryData trajectory_data;
00725   trajectory_data.gravity_constant = data.gravity_constant();
00726   trajectory_data.imu_calibration = {
00727       {data.imu_calibration().w(), data.imu_calibration().x(),
00728        data.imu_calibration().y(), data.imu_calibration().z()}};
00729   if (data.has_fixed_frame_origin_in_map()) {
00730     trajectory_data.fixed_frame_origin_in_map =
00731         transform::ToRigid3(data.fixed_frame_origin_in_map());
00732   }
00733 
00734   const int trajectory_id = data.trajectory_id();
00735   AddWorkItem([this, trajectory_id, trajectory_data]() LOCKS_EXCLUDED(mutex_) {
00736     absl::MutexLock locker(&mutex_);
00737     if (CanAddWorkItemModifying(trajectory_id)) {
00738       optimization_problem_->SetTrajectoryData(trajectory_id, trajectory_data);
00739     }
00740     return WorkItem::Result::kDoNotRunOptimization;
00741   });
00742 }
00743 
00744 void PoseGraph3D::AddNodeToSubmap(const NodeId& node_id,
00745                                   const SubmapId& submap_id) {
00746   AddWorkItem([this, node_id, submap_id]() LOCKS_EXCLUDED(mutex_) {
00747     absl::MutexLock locker(&mutex_);
00748     if (CanAddWorkItemModifying(submap_id.trajectory_id)) {
00749       data_.submap_data.at(submap_id).node_ids.insert(node_id);
00750     }
00751     return WorkItem::Result::kDoNotRunOptimization;
00752   });
00753 }
00754 
00755 void PoseGraph3D::AddSerializedConstraints(
00756     const std::vector<Constraint>& constraints) {
00757   AddWorkItem([this, constraints]() LOCKS_EXCLUDED(mutex_) {
00758     absl::MutexLock locker(&mutex_);
00759     for (const auto& constraint : constraints) {
00760       CHECK(data_.trajectory_nodes.Contains(constraint.node_id));
00761       CHECK(data_.submap_data.Contains(constraint.submap_id));
00762       CHECK(data_.trajectory_nodes.at(constraint.node_id).constant_data !=
00763             nullptr);
00764       CHECK(data_.submap_data.at(constraint.submap_id).submap != nullptr);
00765       switch (constraint.tag) {
00766         case Constraint::Tag::INTRA_SUBMAP:
00767           CHECK(data_.submap_data.at(constraint.submap_id)
00768                     .node_ids.emplace(constraint.node_id)
00769                     .second);
00770           break;
00771         case Constraint::Tag::INTER_SUBMAP:
00772           UpdateTrajectoryConnectivity(constraint);
00773           break;
00774       }
00775       data_.constraints.push_back(constraint);
00776     }
00777     LOG(INFO) << "Loaded " << constraints.size() << " constraints.";
00778     return WorkItem::Result::kDoNotRunOptimization;
00779   });
00780 }
00781 
00782 void PoseGraph3D::AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) {
00783   // C++11 does not allow us to move a unique_ptr into a lambda.
00784   PoseGraphTrimmer* const trimmer_ptr = trimmer.release();
00785   AddWorkItem([this, trimmer_ptr]() LOCKS_EXCLUDED(mutex_) {
00786     absl::MutexLock locker(&mutex_);
00787     trimmers_.emplace_back(trimmer_ptr);
00788     return WorkItem::Result::kDoNotRunOptimization;
00789   });
00790 }
00791 
00792 void PoseGraph3D::RunFinalOptimization() {
00793   {
00794     AddWorkItem([this]() LOCKS_EXCLUDED(mutex_) {
00795       absl::MutexLock locker(&mutex_);
00796       optimization_problem_->SetMaxNumIterations(
00797           options_.max_num_final_iterations());
00798       return WorkItem::Result::kRunOptimization;
00799     });
00800     AddWorkItem([this]() LOCKS_EXCLUDED(mutex_) {
00801       absl::MutexLock locker(&mutex_);
00802       optimization_problem_->SetMaxNumIterations(
00803           options_.optimization_problem_options()
00804               .ceres_solver_options()
00805               .max_num_iterations());
00806       return WorkItem::Result::kDoNotRunOptimization;
00807     });
00808   }
00809   WaitForAllComputations();
00810 }
00811 
00812 void PoseGraph3D::LogResidualHistograms() const {
00813   common::Histogram rotational_residual;
00814   common::Histogram translational_residual;
00815   for (const Constraint& constraint : data_.constraints) {
00816     if (constraint.tag == Constraint::Tag::INTRA_SUBMAP) {
00817       const cartographer::transform::Rigid3d optimized_node_to_map =
00818           data_.trajectory_nodes.at(constraint.node_id).global_pose;
00819       const cartographer::transform::Rigid3d node_to_submap_constraint =
00820           constraint.pose.zbar_ij;
00821       const cartographer::transform::Rigid3d optimized_submap_to_map =
00822           data_.global_submap_poses_3d.at(constraint.submap_id).global_pose;
00823       const cartographer::transform::Rigid3d optimized_node_to_submap =
00824           optimized_submap_to_map.inverse() * optimized_node_to_map;
00825       const cartographer::transform::Rigid3d residual =
00826           node_to_submap_constraint.inverse() * optimized_node_to_submap;
00827       rotational_residual.Add(
00828           common::NormalizeAngleDifference(transform::GetAngle(residual)));
00829       translational_residual.Add(residual.translation().norm());
00830     }
00831   }
00832   LOG(INFO) << "Translational residuals histogram:\n"
00833             << translational_residual.ToString(10);
00834   LOG(INFO) << "Rotational residuals histogram:\n"
00835             << rotational_residual.ToString(10);
00836 }
00837 
00838 void PoseGraph3D::RunOptimization() {
00839   if (optimization_problem_->submap_data().empty()) {
00840     return;
00841   }
00842 
00843   // No other thread is accessing the optimization_problem_, data_.constraints,
00844   // data_.frozen_trajectories and data_.landmark_nodes when executing the
00845   // Solve. Solve is time consuming, so not taking the mutex before Solve to
00846   // avoid blocking foreground processing.
00847   optimization_problem_->Solve(data_.constraints, GetTrajectoryStates(),
00848                                data_.landmark_nodes);
00849   absl::MutexLock locker(&mutex_);
00850 
00851   const auto& submap_data = optimization_problem_->submap_data();
00852   const auto& node_data = optimization_problem_->node_data();
00853   for (const int trajectory_id : node_data.trajectory_ids()) {
00854     for (const auto& node : node_data.trajectory(trajectory_id)) {
00855       data_.trajectory_nodes.at(node.id).global_pose = node.data.global_pose;
00856     }
00857 
00858     // Extrapolate all point cloud poses that were not included in the
00859     // 'optimization_problem_' yet.
00860     const auto local_to_new_global =
00861         ComputeLocalToGlobalTransform(submap_data, trajectory_id);
00862     const auto local_to_old_global = ComputeLocalToGlobalTransform(
00863         data_.global_submap_poses_3d, trajectory_id);
00864     const transform::Rigid3d old_global_to_new_global =
00865         local_to_new_global * local_to_old_global.inverse();
00866 
00867     const NodeId last_optimized_node_id =
00868         std::prev(node_data.EndOfTrajectory(trajectory_id))->id;
00869     auto node_it =
00870         std::next(data_.trajectory_nodes.find(last_optimized_node_id));
00871     for (; node_it != data_.trajectory_nodes.EndOfTrajectory(trajectory_id);
00872          ++node_it) {
00873       auto& mutable_trajectory_node = data_.trajectory_nodes.at(node_it->id);
00874       mutable_trajectory_node.global_pose =
00875           old_global_to_new_global * mutable_trajectory_node.global_pose;
00876     }
00877   }
00878   for (const auto& landmark : optimization_problem_->landmark_data()) {
00879     data_.landmark_nodes[landmark.first].global_landmark_pose = landmark.second;
00880   }
00881   data_.global_submap_poses_3d = submap_data;
00882 
00883   // Log the histograms for the pose residuals.
00884   if (options_.log_residual_histograms()) {
00885     LogResidualHistograms();
00886   }
00887 }
00888 
00889 bool PoseGraph3D::CanAddWorkItemModifying(int trajectory_id) {
00890   auto it = data_.trajectories_state.find(trajectory_id);
00891   if (it == data_.trajectories_state.end()) {
00892     return true;
00893   }
00894   if (it->second.state == TrajectoryState::FINISHED) {
00895     // TODO(gaschler): Replace all FATAL to WARNING after some testing.
00896     LOG(FATAL) << "trajectory_id " << trajectory_id
00897                << " has finished "
00898                   "but modification is requested, skipping.";
00899     return false;
00900   }
00901   if (it->second.deletion_state !=
00902       InternalTrajectoryState::DeletionState::NORMAL) {
00903     LOG(FATAL) << "trajectory_id " << trajectory_id
00904                << " has been scheduled for deletion "
00905                   "but modification is requested, skipping.";
00906     return false;
00907   }
00908   if (it->second.state == TrajectoryState::DELETED) {
00909     LOG(FATAL) << "trajectory_id " << trajectory_id
00910                << " has been deleted "
00911                   "but modification is requested, skipping.";
00912     return false;
00913   }
00914   return true;
00915 }
00916 
00917 MapById<NodeId, TrajectoryNode> PoseGraph3D::GetTrajectoryNodes() const {
00918   absl::MutexLock locker(&mutex_);
00919   return data_.trajectory_nodes;
00920 }
00921 
00922 MapById<NodeId, TrajectoryNodePose> PoseGraph3D::GetTrajectoryNodePoses()
00923     const {
00924   MapById<NodeId, TrajectoryNodePose> node_poses;
00925   absl::MutexLock locker(&mutex_);
00926   for (const auto& node_id_data : data_.trajectory_nodes) {
00927     absl::optional<TrajectoryNodePose::ConstantPoseData> constant_pose_data;
00928     if (node_id_data.data.constant_data != nullptr) {
00929       constant_pose_data = TrajectoryNodePose::ConstantPoseData{
00930           node_id_data.data.constant_data->time,
00931           node_id_data.data.constant_data->local_pose};
00932     }
00933     node_poses.Insert(
00934         node_id_data.id,
00935         TrajectoryNodePose{node_id_data.data.global_pose, constant_pose_data});
00936   }
00937   return node_poses;
00938 }
00939 
00940 std::map<int, PoseGraphInterface::TrajectoryState>
00941 PoseGraph3D::GetTrajectoryStates() const {
00942   std::map<int, PoseGraphInterface::TrajectoryState> trajectories_state;
00943   absl::MutexLock locker(&mutex_);
00944   for (const auto& it : data_.trajectories_state) {
00945     trajectories_state[it.first] = it.second.state;
00946   }
00947   return trajectories_state;
00948 }
00949 
00950 std::map<std::string, transform::Rigid3d> PoseGraph3D::GetLandmarkPoses()
00951     const {
00952   std::map<std::string, transform::Rigid3d> landmark_poses;
00953   absl::MutexLock locker(&mutex_);
00954   for (const auto& landmark : data_.landmark_nodes) {
00955     // Landmark without value has not been optimized yet.
00956     if (!landmark.second.global_landmark_pose.has_value()) continue;
00957     landmark_poses[landmark.first] =
00958         landmark.second.global_landmark_pose.value();
00959   }
00960   return landmark_poses;
00961 }
00962 
00963 void PoseGraph3D::SetLandmarkPose(const std::string& landmark_id,
00964                                   const transform::Rigid3d& global_pose,
00965                                   const bool frozen) {
00966   AddWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00967     absl::MutexLock locker(&mutex_);
00968     data_.landmark_nodes[landmark_id].global_landmark_pose = global_pose;
00969     data_.landmark_nodes[landmark_id].frozen = frozen;
00970     return WorkItem::Result::kDoNotRunOptimization;
00971   });
00972 }
00973 
00974 sensor::MapByTime<sensor::ImuData> PoseGraph3D::GetImuData() const {
00975   absl::MutexLock locker(&mutex_);
00976   return optimization_problem_->imu_data();
00977 }
00978 
00979 sensor::MapByTime<sensor::OdometryData> PoseGraph3D::GetOdometryData() const {
00980   absl::MutexLock locker(&mutex_);
00981   return optimization_problem_->odometry_data();
00982 }
00983 
00984 sensor::MapByTime<sensor::FixedFramePoseData>
00985 PoseGraph3D::GetFixedFramePoseData() const {
00986   absl::MutexLock locker(&mutex_);
00987   return optimization_problem_->fixed_frame_pose_data();
00988 }
00989 
00990 std::map<std::string /* landmark ID */, PoseGraphInterface::LandmarkNode>
00991 PoseGraph3D::GetLandmarkNodes() const {
00992   absl::MutexLock locker(&mutex_);
00993   return data_.landmark_nodes;
00994 }
00995 
00996 std::map<int, PoseGraphInterface::TrajectoryData>
00997 PoseGraph3D::GetTrajectoryData() const {
00998   absl::MutexLock locker(&mutex_);
00999   return optimization_problem_->trajectory_data();
01000 }
01001 
01002 std::vector<PoseGraphInterface::Constraint> PoseGraph3D::constraints() const {
01003   absl::MutexLock locker(&mutex_);
01004   return data_.constraints;
01005 }
01006 
01007 void PoseGraph3D::SetInitialTrajectoryPose(const int from_trajectory_id,
01008                                            const int to_trajectory_id,
01009                                            const transform::Rigid3d& pose,
01010                                            const common::Time time) {
01011   absl::MutexLock locker(&mutex_);
01012   data_.initial_trajectory_poses[from_trajectory_id] =
01013       InitialTrajectoryPose{to_trajectory_id, pose, time};
01014 }
01015 
01016 transform::Rigid3d PoseGraph3D::GetInterpolatedGlobalTrajectoryPose(
01017     const int trajectory_id, const common::Time time) const {
01018   CHECK_GT(data_.trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 0);
01019   const auto it = data_.trajectory_nodes.lower_bound(trajectory_id, time);
01020   if (it == data_.trajectory_nodes.BeginOfTrajectory(trajectory_id)) {
01021     return data_.trajectory_nodes.BeginOfTrajectory(trajectory_id)
01022         ->data.global_pose;
01023   }
01024   if (it == data_.trajectory_nodes.EndOfTrajectory(trajectory_id)) {
01025     return std::prev(data_.trajectory_nodes.EndOfTrajectory(trajectory_id))
01026         ->data.global_pose;
01027   }
01028   return transform::Interpolate(
01029              transform::TimestampedTransform{std::prev(it)->data.time(),
01030                                              std::prev(it)->data.global_pose},
01031              transform::TimestampedTransform{it->data.time(),
01032                                              it->data.global_pose},
01033              time)
01034       .transform;
01035 }
01036 
01037 transform::Rigid3d PoseGraph3D::GetLocalToGlobalTransform(
01038     const int trajectory_id) const {
01039   absl::MutexLock locker(&mutex_);
01040   return ComputeLocalToGlobalTransform(data_.global_submap_poses_3d,
01041                                        trajectory_id);
01042 }
01043 
01044 std::vector<std::vector<int>> PoseGraph3D::GetConnectedTrajectories() const {
01045   absl::MutexLock locker(&mutex_);
01046   return data_.trajectory_connectivity_state.Components();
01047 }
01048 
01049 PoseGraphInterface::SubmapData PoseGraph3D::GetSubmapData(
01050     const SubmapId& submap_id) const {
01051   absl::MutexLock locker(&mutex_);
01052   return GetSubmapDataUnderLock(submap_id);
01053 }
01054 
01055 MapById<SubmapId, PoseGraphInterface::SubmapData>
01056 PoseGraph3D::GetAllSubmapData() const {
01057   absl::MutexLock locker(&mutex_);
01058   return GetSubmapDataUnderLock();
01059 }
01060 
01061 MapById<SubmapId, PoseGraphInterface::SubmapPose>
01062 PoseGraph3D::GetAllSubmapPoses() const {
01063   absl::MutexLock locker(&mutex_);
01064   MapById<SubmapId, SubmapPose> submap_poses;
01065   for (const auto& submap_id_data : data_.submap_data) {
01066     auto submap_data = GetSubmapDataUnderLock(submap_id_data.id);
01067     submap_poses.Insert(
01068         submap_id_data.id,
01069         PoseGraphInterface::SubmapPose{submap_data.submap->num_range_data(),
01070                                        submap_data.pose});
01071   }
01072   return submap_poses;
01073 }
01074 
01075 transform::Rigid3d PoseGraph3D::ComputeLocalToGlobalTransform(
01076     const MapById<SubmapId, optimization::SubmapSpec3D>& global_submap_poses,
01077     const int trajectory_id) const {
01078   auto begin_it = global_submap_poses.BeginOfTrajectory(trajectory_id);
01079   auto end_it = global_submap_poses.EndOfTrajectory(trajectory_id);
01080   if (begin_it == end_it) {
01081     const auto it = data_.initial_trajectory_poses.find(trajectory_id);
01082     if (it != data_.initial_trajectory_poses.end()) {
01083       return GetInterpolatedGlobalTrajectoryPose(it->second.to_trajectory_id,
01084                                                  it->second.time) *
01085              it->second.relative_pose;
01086     } else {
01087       return transform::Rigid3d::Identity();
01088     }
01089   }
01090   const SubmapId last_optimized_submap_id = std::prev(end_it)->id;
01091   // Accessing 'local_pose' in Submap is okay, since the member is const.
01092   return global_submap_poses.at(last_optimized_submap_id).global_pose *
01093          data_.submap_data.at(last_optimized_submap_id)
01094              .submap->local_pose()
01095              .inverse();
01096 }
01097 
01098 PoseGraphInterface::SubmapData PoseGraph3D::GetSubmapDataUnderLock(
01099     const SubmapId& submap_id) const {
01100   const auto it = data_.submap_data.find(submap_id);
01101   if (it == data_.submap_data.end()) {
01102     return {};
01103   }
01104   auto submap = it->data.submap;
01105   if (data_.global_submap_poses_3d.Contains(submap_id)) {
01106     // We already have an optimized pose.
01107     return {submap, data_.global_submap_poses_3d.at(submap_id).global_pose};
01108   }
01109   // We have to extrapolate.
01110   return {submap, ComputeLocalToGlobalTransform(data_.global_submap_poses_3d,
01111                                                 submap_id.trajectory_id) *
01112                       submap->local_pose()};
01113 }
01114 
01115 PoseGraph3D::TrimmingHandle::TrimmingHandle(PoseGraph3D* const parent)
01116     : parent_(parent) {}
01117 
01118 int PoseGraph3D::TrimmingHandle::num_submaps(const int trajectory_id) const {
01119   const auto& submap_data = parent_->optimization_problem_->submap_data();
01120   return submap_data.SizeOfTrajectoryOrZero(trajectory_id);
01121 }
01122 
01123 std::vector<SubmapId> PoseGraph3D::TrimmingHandle::GetSubmapIds(
01124     int trajectory_id) const {
01125   std::vector<SubmapId> submap_ids;
01126   const auto& submap_data = parent_->optimization_problem_->submap_data();
01127   for (const auto& it : submap_data.trajectory(trajectory_id)) {
01128     submap_ids.push_back(it.id);
01129   }
01130   return submap_ids;
01131 }
01132 MapById<SubmapId, PoseGraphInterface::SubmapData>
01133 PoseGraph3D::TrimmingHandle::GetOptimizedSubmapData() const {
01134   MapById<SubmapId, PoseGraphInterface::SubmapData> submaps;
01135   for (const auto& submap_id_data : parent_->data_.submap_data) {
01136     if (submap_id_data.data.state != SubmapState::kFinished ||
01137         !parent_->data_.global_submap_poses_3d.Contains(submap_id_data.id)) {
01138       continue;
01139     }
01140     submaps.Insert(
01141         submap_id_data.id,
01142         SubmapData{submap_id_data.data.submap,
01143                    parent_->data_.global_submap_poses_3d.at(submap_id_data.id)
01144                        .global_pose});
01145   }
01146   return submaps;
01147 }
01148 
01149 const MapById<NodeId, TrajectoryNode>&
01150 PoseGraph3D::TrimmingHandle::GetTrajectoryNodes() const {
01151   return parent_->data_.trajectory_nodes;
01152 }
01153 
01154 const std::vector<PoseGraphInterface::Constraint>&
01155 PoseGraph3D::TrimmingHandle::GetConstraints() const {
01156   return parent_->data_.constraints;
01157 }
01158 
01159 bool PoseGraph3D::TrimmingHandle::IsFinished(const int trajectory_id) const {
01160   return parent_->IsTrajectoryFinished(trajectory_id);
01161 }
01162 
01163 void PoseGraph3D::TrimmingHandle::SetTrajectoryState(int trajectory_id,
01164                                                      TrajectoryState state) {
01165   parent_->data_.trajectories_state[trajectory_id].state = state;
01166 }
01167 
01168 void PoseGraph3D::TrimmingHandle::TrimSubmap(const SubmapId& submap_id) {
01169   // TODO(hrapp): We have to make sure that the trajectory has been finished
01170   // if we want to delete the last submaps.
01171   CHECK(parent_->data_.submap_data.at(submap_id).state ==
01172         SubmapState::kFinished);
01173 
01174   // Compile all nodes that are still INTRA_SUBMAP constrained once the submap
01175   // with 'submap_id' is gone.
01176   std::set<NodeId> nodes_to_retain;
01177   for (const Constraint& constraint : parent_->data_.constraints) {
01178     if (constraint.tag == Constraint::Tag::INTRA_SUBMAP &&
01179         constraint.submap_id != submap_id) {
01180       nodes_to_retain.insert(constraint.node_id);
01181     }
01182   }
01183   // Remove all 'data_.constraints' related to 'submap_id'.
01184   std::set<NodeId> nodes_to_remove;
01185   {
01186     std::vector<Constraint> constraints;
01187     for (const Constraint& constraint : parent_->data_.constraints) {
01188       if (constraint.submap_id == submap_id) {
01189         if (constraint.tag == Constraint::Tag::INTRA_SUBMAP &&
01190             nodes_to_retain.count(constraint.node_id) == 0) {
01191           // This node will no longer be INTRA_SUBMAP contrained and has to be
01192           // removed.
01193           nodes_to_remove.insert(constraint.node_id);
01194         }
01195       } else {
01196         constraints.push_back(constraint);
01197       }
01198     }
01199     parent_->data_.constraints = std::move(constraints);
01200   }
01201   // Remove all 'data_.constraints' related to 'nodes_to_remove'.
01202   {
01203     std::vector<Constraint> constraints;
01204     for (const Constraint& constraint : parent_->data_.constraints) {
01205       if (nodes_to_remove.count(constraint.node_id) == 0) {
01206         constraints.push_back(constraint);
01207       }
01208     }
01209     parent_->data_.constraints = std::move(constraints);
01210   }
01211 
01212   // Mark the submap with 'submap_id' as trimmed and remove its data.
01213   CHECK(parent_->data_.submap_data.at(submap_id).state ==
01214         SubmapState::kFinished);
01215   parent_->data_.submap_data.Trim(submap_id);
01216   parent_->constraint_builder_.DeleteScanMatcher(submap_id);
01217   parent_->optimization_problem_->TrimSubmap(submap_id);
01218 
01219   // We have one submap less, update the gauge metrics.
01220   kDeletedSubmapsMetric->Increment();
01221   if (parent_->IsTrajectoryFrozen(submap_id.trajectory_id)) {
01222     kFrozenSubmapsMetric->Decrement();
01223   } else {
01224     kActiveSubmapsMetric->Decrement();
01225   }
01226 
01227   // Remove the 'nodes_to_remove' from the pose graph and the optimization
01228   // problem.
01229   for (const NodeId& node_id : nodes_to_remove) {
01230     parent_->data_.trajectory_nodes.Trim(node_id);
01231     parent_->optimization_problem_->TrimTrajectoryNode(node_id);
01232   }
01233 }
01234 
01235 MapById<SubmapId, PoseGraphInterface::SubmapData>
01236 PoseGraph3D::GetSubmapDataUnderLock() const {
01237   MapById<SubmapId, PoseGraphInterface::SubmapData> submaps;
01238   for (const auto& submap_id_data : data_.submap_data) {
01239     submaps.Insert(submap_id_data.id,
01240                    GetSubmapDataUnderLock(submap_id_data.id));
01241   }
01242   return submaps;
01243 }
01244 
01245 void PoseGraph3D::SetGlobalSlamOptimizationCallback(
01246     PoseGraphInterface::GlobalSlamOptimizationCallback callback) {
01247   global_slam_optimization_callback_ = callback;
01248 }
01249 
01250 void PoseGraph3D::RegisterMetrics(metrics::FamilyFactory* family_factory) {
01251   auto* latency = family_factory->NewGaugeFamily(
01252       "mapping_3d_pose_graph_work_queue_delay",
01253       "Age of the oldest entry in the work queue in seconds");
01254   kWorkQueueDelayMetric = latency->Add({});
01255   auto* constraints = family_factory->NewGaugeFamily(
01256       "mapping_3d_pose_graph_constraints",
01257       "Current number of constraints in the pose graph");
01258   kConstraintsDifferentTrajectoryMetric =
01259       constraints->Add({{"tag", "inter_submap"}, {"trajectory", "different"}});
01260   kConstraintsSameTrajectoryMetric =
01261       constraints->Add({{"tag", "inter_submap"}, {"trajectory", "same"}});
01262   auto* submaps = family_factory->NewGaugeFamily(
01263       "mapping_3d_pose_graph_submaps", "Number of submaps in the pose graph.");
01264   kActiveSubmapsMetric = submaps->Add({{"state", "active"}});
01265   kFrozenSubmapsMetric = submaps->Add({{"state", "frozen"}});
01266   kDeletedSubmapsMetric = submaps->Add({{"state", "deleted"}});
01267 }
01268 
01269 }  // namespace mapping
01270 }  // namespace cartographer


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