constraint_builder_2d.h
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 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_2D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_2D_H_
00019 
00020 #include <array>
00021 #include <deque>
00022 #include <functional>
00023 #include <limits>
00024 #include <vector>
00025 
00026 #include "Eigen/Core"
00027 #include "Eigen/Geometry"
00028 #include "absl/synchronization/mutex.h"
00029 #include "cartographer/common/fixed_ratio_sampler.h"
00030 #include "cartographer/common/histogram.h"
00031 #include "cartographer/common/math.h"
00032 #include "cartographer/common/task.h"
00033 #include "cartographer/common/thread_pool.h"
00034 #include "cartographer/mapping/2d/submap_2d.h"
00035 #include "cartographer/mapping/internal/2d/scan_matching/ceres_scan_matcher_2d.h"
00036 #include "cartographer/mapping/internal/2d/scan_matching/fast_correlative_scan_matcher_2d.h"
00037 #include "cartographer/mapping/pose_graph_interface.h"
00038 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h"
00039 #include "cartographer/metrics/family_factory.h"
00040 #include "cartographer/sensor/internal/voxel_filter.h"
00041 #include "cartographer/sensor/point_cloud.h"
00042 
00043 namespace cartographer {
00044 namespace mapping {
00045 namespace constraints {
00046 
00047 // Returns (map <- submap) where 'submap' is a coordinate system at the origin
00048 // of the Submap.
00049 transform::Rigid2d ComputeSubmapPose(const Submap2D& submap);
00050 
00051 // Asynchronously computes constraints.
00052 //
00053 // Intermingle an arbitrary number of calls to 'MaybeAddConstraint',
00054 // 'MaybeAddGlobalConstraint', and 'NotifyEndOfNode', then call 'WhenDone' once.
00055 // After all computations are done the 'callback' will be called with the result
00056 // and another MaybeAdd(Global)Constraint()/WhenDone() cycle can follow.
00057 //
00058 // This class is thread-safe.
00059 class ConstraintBuilder2D {
00060  public:
00061   using Constraint = PoseGraphInterface::Constraint;
00062   using Result = std::vector<Constraint>;
00063 
00064   ConstraintBuilder2D(const proto::ConstraintBuilderOptions& options,
00065                       common::ThreadPoolInterface* thread_pool);
00066   ~ConstraintBuilder2D();
00067 
00068   ConstraintBuilder2D(const ConstraintBuilder2D&) = delete;
00069   ConstraintBuilder2D& operator=(const ConstraintBuilder2D&) = delete;
00070 
00071   // Schedules exploring a new constraint between 'submap' identified by
00072   // 'submap_id', and the 'compressed_point_cloud' for 'node_id'. The
00073   // 'initial_relative_pose' is relative to the 'submap'.
00074   //
00075   // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
00076   // all computations are finished.
00077   void MaybeAddConstraint(const SubmapId& submap_id, const Submap2D* submap,
00078                           const NodeId& node_id,
00079                           const TrajectoryNode::Data* const constant_data,
00080                           const transform::Rigid2d& initial_relative_pose);
00081 
00082   // Schedules exploring a new constraint between 'submap' identified by
00083   // 'submap_id' and the 'compressed_point_cloud' for 'node_id'.
00084   // This performs full-submap matching.
00085   //
00086   // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
00087   // all computations are finished.
00088   void MaybeAddGlobalConstraint(
00089       const SubmapId& submap_id, const Submap2D* submap, const NodeId& node_id,
00090       const TrajectoryNode::Data* const constant_data);
00091 
00092   // Must be called after all computations related to one node have been added.
00093   void NotifyEndOfNode();
00094 
00095   // Registers the 'callback' to be called with the results, after all
00096   // computations triggered by 'MaybeAdd*Constraint' have finished.
00097   // 'callback' is executed in the 'ThreadPool'.
00098   void WhenDone(const std::function<void(const Result&)>& callback);
00099 
00100   // Returns the number of consecutive finished nodes.
00101   int GetNumFinishedNodes();
00102 
00103   // Delete data related to 'submap_id'.
00104   void DeleteScanMatcher(const SubmapId& submap_id);
00105 
00106   static void RegisterMetrics(metrics::FamilyFactory* family_factory);
00107 
00108  private:
00109   struct SubmapScanMatcher {
00110     const Grid2D* grid = nullptr;
00111     std::unique_ptr<scan_matching::FastCorrelativeScanMatcher2D>
00112         fast_correlative_scan_matcher;
00113     std::weak_ptr<common::Task> creation_task_handle;
00114   };
00115 
00116   // The returned 'grid' and 'fast_correlative_scan_matcher' must only be
00117   // accessed after 'creation_task_handle' has completed.
00118   const SubmapScanMatcher* DispatchScanMatcherConstruction(
00119       const SubmapId& submap_id, const Grid2D* grid)
00120       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00121 
00122   // Runs in a background thread and does computations for an additional
00123   // constraint, assuming 'submap' and 'compressed_point_cloud' do not change
00124   // anymore. As output, it may create a new Constraint in 'constraint'.
00125   void ComputeConstraint(const SubmapId& submap_id, const Submap2D* submap,
00126                          const NodeId& node_id, bool match_full_submap,
00127                          const TrajectoryNode::Data* const constant_data,
00128                          const transform::Rigid2d& initial_relative_pose,
00129                          const SubmapScanMatcher& submap_scan_matcher,
00130                          std::unique_ptr<Constraint>* constraint)
00131       LOCKS_EXCLUDED(mutex_);
00132 
00133   void RunWhenDoneCallback() LOCKS_EXCLUDED(mutex_);
00134 
00135   const constraints::proto::ConstraintBuilderOptions options_;
00136   common::ThreadPoolInterface* thread_pool_;
00137   absl::Mutex mutex_;
00138 
00139   // 'callback' set by WhenDone().
00140   std::unique_ptr<std::function<void(const Result&)>> when_done_
00141       GUARDED_BY(mutex_);
00142 
00143   // TODO(gaschler): Use atomics instead of mutex to access these counters.
00144   // Number of the node in reaction to which computations are currently
00145   // added. This is always the number of nodes seen so far, even when older
00146   // nodes are matched against a new submap.
00147   int num_started_nodes_ GUARDED_BY(mutex_) = 0;
00148 
00149   int num_finished_nodes_ GUARDED_BY(mutex_) = 0;
00150 
00151   std::unique_ptr<common::Task> finish_node_task_ GUARDED_BY(mutex_);
00152 
00153   std::unique_ptr<common::Task> when_done_task_ GUARDED_BY(mutex_);
00154 
00155   // Constraints currently being computed in the background. A deque is used to
00156   // keep pointers valid when adding more entries. Constraint search results
00157   // with below-threshold scores are also 'nullptr'.
00158   std::deque<std::unique_ptr<Constraint>> constraints_ GUARDED_BY(mutex_);
00159 
00160   // Map of dispatched or constructed scan matchers by 'submap_id'.
00161   std::map<SubmapId, SubmapScanMatcher> submap_scan_matchers_
00162       GUARDED_BY(mutex_);
00163 
00164   common::FixedRatioSampler sampler_;
00165   scan_matching::CeresScanMatcher2D ceres_scan_matcher_;
00166 
00167   // Histogram of scan matcher scores.
00168   common::Histogram score_histogram_ GUARDED_BY(mutex_);
00169 };
00170 
00171 }  // namespace constraints
00172 }  // namespace mapping
00173 }  // namespace cartographer
00174 
00175 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_2D_H_


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