global_trajectory_builder.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 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 <memory>
20 
25 #include "glog/logging.h"
26 
27 namespace cartographer {
28 namespace mapping {
29 namespace {
30 
31 static auto* kLocalSlamMatchingResults = metrics::Counter::Null();
32 static auto* kLocalSlamInsertionResults = metrics::Counter::Null();
33 
34 template <typename LocalTrajectoryBuilder, typename PoseGraph>
35 class GlobalTrajectoryBuilder : public mapping::TrajectoryBuilderInterface {
36  public:
37  // Passing a 'nullptr' for 'local_trajectory_builder' is acceptable, but no
38  // 'TimedPointCloudData' may be added in that case.
39  GlobalTrajectoryBuilder(
40  std::unique_ptr<LocalTrajectoryBuilder> local_trajectory_builder,
41  const int trajectory_id, PoseGraph* const pose_graph,
42  const LocalSlamResultCallback& local_slam_result_callback)
43  : trajectory_id_(trajectory_id),
44  pose_graph_(pose_graph),
45  local_trajectory_builder_(std::move(local_trajectory_builder)),
46  local_slam_result_callback_(local_slam_result_callback) {}
47  ~GlobalTrajectoryBuilder() override {}
48 
49  GlobalTrajectoryBuilder(const GlobalTrajectoryBuilder&) = delete;
50  GlobalTrajectoryBuilder& operator=(const GlobalTrajectoryBuilder&) = delete;
51 
52  void AddSensorData(
53  const std::string& sensor_id,
54  const sensor::TimedPointCloudData& timed_point_cloud_data) override {
56  << "Cannot add TimedPointCloudData without a LocalTrajectoryBuilder.";
57  std::unique_ptr<typename LocalTrajectoryBuilder::MatchingResult>
58  matching_result = local_trajectory_builder_->AddRangeData(
59  sensor_id, timed_point_cloud_data);
60  if (matching_result == nullptr) {
61  // The range data has not been fully accumulated yet.
62  return;
63  }
64  kLocalSlamMatchingResults->Increment();
65  std::unique_ptr<InsertionResult> insertion_result;
66  if (matching_result->insertion_result != nullptr) {
67  kLocalSlamInsertionResults->Increment();
68  auto node_id = pose_graph_->AddNode(
69  matching_result->insertion_result->constant_data, trajectory_id_,
70  matching_result->insertion_result->insertion_submaps);
71  CHECK_EQ(node_id.trajectory_id, trajectory_id_);
72  insertion_result = common::make_unique<InsertionResult>(InsertionResult{
73  node_id, matching_result->insertion_result->constant_data,
74  std::vector<std::shared_ptr<const Submap>>(
75  matching_result->insertion_result->insertion_submaps.begin(),
76  matching_result->insertion_result->insertion_submaps.end())});
77  }
80  trajectory_id_, matching_result->time, matching_result->local_pose,
81  std::move(matching_result->range_data_in_local),
82  std::move(insertion_result));
83  }
84  }
85 
86  void AddSensorData(const std::string& sensor_id,
87  const sensor::ImuData& imu_data) override {
89  local_trajectory_builder_->AddImuData(imu_data);
90  }
91  pose_graph_->AddImuData(trajectory_id_, imu_data);
92  }
93 
94  void AddSensorData(const std::string& sensor_id,
95  const sensor::OdometryData& odometry_data) override {
96  CHECK(odometry_data.pose.IsValid()) << odometry_data.pose;
98  local_trajectory_builder_->AddOdometryData(odometry_data);
99  }
100  pose_graph_->AddOdometryData(trajectory_id_, odometry_data);
101  }
102 
103  void AddSensorData(
104  const std::string& sensor_id,
105  const sensor::FixedFramePoseData& fixed_frame_pose) override {
106  if (fixed_frame_pose.pose.has_value()) {
107  CHECK(fixed_frame_pose.pose.value().IsValid())
108  << fixed_frame_pose.pose.value();
109  }
110  pose_graph_->AddFixedFramePoseData(trajectory_id_, fixed_frame_pose);
111  }
112 
113  void AddSensorData(const std::string& sensor_id,
114  const sensor::LandmarkData& landmark_data) override {
115  pose_graph_->AddLandmarkData(trajectory_id_, landmark_data);
116  }
117 
118  void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
119  local_slam_result_data) override {
120  CHECK(!local_trajectory_builder_) << "Can't add LocalSlamResultData with "
121  "local_trajectory_builder_ present.";
122  local_slam_result_data->AddToPoseGraph(trajectory_id_, pose_graph_);
123  }
124 
125  private:
126  const int trajectory_id_;
127  PoseGraph* const pose_graph_;
128  std::unique_ptr<LocalTrajectoryBuilder> local_trajectory_builder_;
129  LocalSlamResultCallback local_slam_result_callback_;
130 };
131 
132 } // namespace
133 
134 std::unique_ptr<TrajectoryBuilderInterface> CreateGlobalTrajectoryBuilder2D(
135  std::unique_ptr<LocalTrajectoryBuilder2D> local_trajectory_builder,
136  const int trajectory_id, mapping::PoseGraph2D* const pose_graph,
138  local_slam_result_callback) {
139  return common::make_unique<
140  GlobalTrajectoryBuilder<LocalTrajectoryBuilder2D, mapping::PoseGraph2D>>(
141  std::move(local_trajectory_builder), trajectory_id, pose_graph,
142  local_slam_result_callback);
143 }
144 
145 std::unique_ptr<TrajectoryBuilderInterface> CreateGlobalTrajectoryBuilder3D(
146  std::unique_ptr<LocalTrajectoryBuilder3D> local_trajectory_builder,
147  const int trajectory_id, mapping::PoseGraph3D* const pose_graph,
149  local_slam_result_callback) {
150  return common::make_unique<
151  GlobalTrajectoryBuilder<LocalTrajectoryBuilder3D, mapping::PoseGraph3D>>(
152  std::move(local_trajectory_builder), trajectory_id, pose_graph,
153  local_slam_result_callback);
154 }
155 
157  auto* results = factory->NewCounterFamily(
158  "mapping_internal_global_trajectory_builder_local_slam_results",
159  "Local SLAM results");
160  kLocalSlamMatchingResults = results->Add({{"type", "MatchingResult"}});
161  kLocalSlamInsertionResults = results->Add({{"type", "InsertionResult"}});
162 }
163 
164 } // namespace mapping
165 } // namespace cartographer
std::unique_ptr< TrajectoryBuilderInterface > CreateGlobalTrajectoryBuilder2D(std::unique_ptr< LocalTrajectoryBuilder2D > local_trajectory_builder, const int trajectory_id, mapping::PoseGraph2D *const pose_graph, const TrajectoryBuilderInterface::LocalSlamResultCallback &local_slam_result_callback)
LocalSlamResultCallback local_slam_result_callback_
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
void GlobalTrajectoryBuilderRegisterMetrics(metrics::FamilyFactory *factory)
virtual Family< Counter > * NewCounterFamily(const std::string &name, const std::string &description)=0
std::unique_ptr< LocalTrajectoryBuilder > local_trajectory_builder_
std::unique_ptr< TrajectoryBuilderInterface > CreateGlobalTrajectoryBuilder3D(std::unique_ptr< LocalTrajectoryBuilder3D > local_trajectory_builder, const int trajectory_id, mapping::PoseGraph3D *const pose_graph, const TrajectoryBuilderInterface::LocalSlamResultCallback &local_slam_result_callback)
static Counter * Null()
Definition: counter.cc:33
PoseGraph *const pose_graph_
const int trajectory_id_
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback


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