global_trajectory_builder.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 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/global_trajectory_builder.h"
00018 
00019 #include <memory>
00020 
00021 #include "absl/memory/memory.h"
00022 #include "cartographer/common/time.h"
00023 #include "cartographer/mapping/local_slam_result_data.h"
00024 #include "cartographer/metrics/family_factory.h"
00025 #include "glog/logging.h"
00026 
00027 namespace cartographer {
00028 namespace mapping {
00029 namespace {
00030 
00031 static auto* kLocalSlamMatchingResults = metrics::Counter::Null();
00032 static auto* kLocalSlamInsertionResults = metrics::Counter::Null();
00033 
00034 template <typename LocalTrajectoryBuilder, typename PoseGraph>
00035 class GlobalTrajectoryBuilder : public mapping::TrajectoryBuilderInterface {
00036  public:
00037   // Passing a 'nullptr' for 'local_trajectory_builder' is acceptable, but no
00038   // 'TimedPointCloudData' may be added in that case.
00039   GlobalTrajectoryBuilder(
00040       std::unique_ptr<LocalTrajectoryBuilder> local_trajectory_builder,
00041       const int trajectory_id, PoseGraph* const pose_graph,
00042       const LocalSlamResultCallback& local_slam_result_callback)
00043       : trajectory_id_(trajectory_id),
00044         pose_graph_(pose_graph),
00045         local_trajectory_builder_(std::move(local_trajectory_builder)),
00046         local_slam_result_callback_(local_slam_result_callback) {}
00047   ~GlobalTrajectoryBuilder() override {}
00048 
00049   GlobalTrajectoryBuilder(const GlobalTrajectoryBuilder&) = delete;
00050   GlobalTrajectoryBuilder& operator=(const GlobalTrajectoryBuilder&) = delete;
00051 
00052   void AddSensorData(
00053       const std::string& sensor_id,
00054       const sensor::TimedPointCloudData& timed_point_cloud_data) override {
00055     CHECK(local_trajectory_builder_)
00056         << "Cannot add TimedPointCloudData without a LocalTrajectoryBuilder.";
00057     std::unique_ptr<typename LocalTrajectoryBuilder::MatchingResult>
00058         matching_result = local_trajectory_builder_->AddRangeData(
00059             sensor_id, timed_point_cloud_data);
00060     if (matching_result == nullptr) {
00061       // The range data has not been fully accumulated yet.
00062       return;
00063     }
00064     kLocalSlamMatchingResults->Increment();
00065     std::unique_ptr<InsertionResult> insertion_result;
00066     if (matching_result->insertion_result != nullptr) {
00067       kLocalSlamInsertionResults->Increment();
00068       auto node_id = pose_graph_->AddNode(
00069           matching_result->insertion_result->constant_data, trajectory_id_,
00070           matching_result->insertion_result->insertion_submaps);
00071       CHECK_EQ(node_id.trajectory_id, trajectory_id_);
00072       insertion_result = absl::make_unique<InsertionResult>(InsertionResult{
00073           node_id, matching_result->insertion_result->constant_data,
00074           std::vector<std::shared_ptr<const Submap>>(
00075               matching_result->insertion_result->insertion_submaps.begin(),
00076               matching_result->insertion_result->insertion_submaps.end())});
00077     }
00078     if (local_slam_result_callback_) {
00079       local_slam_result_callback_(
00080           trajectory_id_, matching_result->time, matching_result->local_pose,
00081           std::move(matching_result->range_data_in_local),
00082           std::move(insertion_result));
00083     }
00084   }
00085 
00086   void AddSensorData(const std::string& sensor_id,
00087                      const sensor::ImuData& imu_data) override {
00088     if (local_trajectory_builder_) {
00089       local_trajectory_builder_->AddImuData(imu_data);
00090     }
00091     pose_graph_->AddImuData(trajectory_id_, imu_data);
00092   }
00093 
00094   void AddSensorData(const std::string& sensor_id,
00095                      const sensor::OdometryData& odometry_data) override {
00096     CHECK(odometry_data.pose.IsValid()) << odometry_data.pose;
00097     if (local_trajectory_builder_) {
00098       local_trajectory_builder_->AddOdometryData(odometry_data);
00099     }
00100     pose_graph_->AddOdometryData(trajectory_id_, odometry_data);
00101   }
00102 
00103   void AddSensorData(
00104       const std::string& sensor_id,
00105       const sensor::FixedFramePoseData& fixed_frame_pose) override {
00106     if (fixed_frame_pose.pose.has_value()) {
00107       CHECK(fixed_frame_pose.pose.value().IsValid())
00108           << fixed_frame_pose.pose.value();
00109     }
00110     pose_graph_->AddFixedFramePoseData(trajectory_id_, fixed_frame_pose);
00111   }
00112 
00113   void AddSensorData(const std::string& sensor_id,
00114                      const sensor::LandmarkData& landmark_data) override {
00115     pose_graph_->AddLandmarkData(trajectory_id_, landmark_data);
00116   }
00117 
00118   void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
00119                                   local_slam_result_data) override {
00120     CHECK(!local_trajectory_builder_) << "Can't add LocalSlamResultData with "
00121                                          "local_trajectory_builder_ present.";
00122     local_slam_result_data->AddToPoseGraph(trajectory_id_, pose_graph_);
00123   }
00124 
00125  private:
00126   const int trajectory_id_;
00127   PoseGraph* const pose_graph_;
00128   std::unique_ptr<LocalTrajectoryBuilder> local_trajectory_builder_;
00129   LocalSlamResultCallback local_slam_result_callback_;
00130 };
00131 
00132 }  // namespace
00133 
00134 std::unique_ptr<TrajectoryBuilderInterface> CreateGlobalTrajectoryBuilder2D(
00135     std::unique_ptr<LocalTrajectoryBuilder2D> local_trajectory_builder,
00136     const int trajectory_id, mapping::PoseGraph2D* const pose_graph,
00137     const TrajectoryBuilderInterface::LocalSlamResultCallback&
00138         local_slam_result_callback) {
00139   return absl::make_unique<
00140       GlobalTrajectoryBuilder<LocalTrajectoryBuilder2D, mapping::PoseGraph2D>>(
00141       std::move(local_trajectory_builder), trajectory_id, pose_graph,
00142       local_slam_result_callback);
00143 }
00144 
00145 std::unique_ptr<TrajectoryBuilderInterface> CreateGlobalTrajectoryBuilder3D(
00146     std::unique_ptr<LocalTrajectoryBuilder3D> local_trajectory_builder,
00147     const int trajectory_id, mapping::PoseGraph3D* const pose_graph,
00148     const TrajectoryBuilderInterface::LocalSlamResultCallback&
00149         local_slam_result_callback) {
00150   return absl::make_unique<
00151       GlobalTrajectoryBuilder<LocalTrajectoryBuilder3D, mapping::PoseGraph3D>>(
00152       std::move(local_trajectory_builder), trajectory_id, pose_graph,
00153       local_slam_result_callback);
00154 }
00155 
00156 void GlobalTrajectoryBuilderRegisterMetrics(metrics::FamilyFactory* factory) {
00157   auto* results = factory->NewCounterFamily(
00158       "mapping_global_trajectory_builder_local_slam_results",
00159       "Local SLAM results");
00160   kLocalSlamMatchingResults = results->Add({{"type", "MatchingResult"}});
00161   kLocalSlamInsertionResults = results->Add({{"type", "InsertionResult"}});
00162 }
00163 
00164 }  // namespace mapping
00165 }  // namespace cartographer


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