pose_graph_3d.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_3D_POSE_GRAPH_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_
00019 
00020 #include <deque>
00021 #include <functional>
00022 #include <limits>
00023 #include <map>
00024 #include <memory>
00025 #include <set>
00026 #include <vector>
00027 
00028 #include "Eigen/Core"
00029 #include "Eigen/Geometry"
00030 #include "absl/container/flat_hash_map.h"
00031 #include "absl/synchronization/mutex.h"
00032 #include "cartographer/common/fixed_ratio_sampler.h"
00033 #include "cartographer/common/thread_pool.h"
00034 #include "cartographer/common/time.h"
00035 #include "cartographer/mapping/3d/submap_3d.h"
00036 #include "cartographer/mapping/internal/constraints/constraint_builder_3d.h"
00037 #include "cartographer/mapping/internal/optimization/optimization_problem_3d.h"
00038 #include "cartographer/mapping/internal/trajectory_connectivity_state.h"
00039 #include "cartographer/mapping/internal/work_queue.h"
00040 #include "cartographer/mapping/pose_graph.h"
00041 #include "cartographer/mapping/pose_graph_data.h"
00042 #include "cartographer/mapping/pose_graph_trimmer.h"
00043 #include "cartographer/metrics/family_factory.h"
00044 #include "cartographer/sensor/fixed_frame_pose_data.h"
00045 #include "cartographer/sensor/landmark_data.h"
00046 #include "cartographer/sensor/odometry_data.h"
00047 #include "cartographer/sensor/point_cloud.h"
00048 #include "cartographer/transform/transform.h"
00049 
00050 namespace cartographer {
00051 namespace mapping {
00052 
00053 // Implements the loop closure method called Sparse Pose Adjustment (SPA) from
00054 // Konolige, Kurt, et al. "Efficient sparse pose adjustment for 2d mapping."
00055 // Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ International Conference
00056 // on (pp. 22--29). IEEE, 2010.
00057 //
00058 // It is extended for submapping in 3D:
00059 // Each node has been matched against one or more submaps (adding a constraint
00060 // for each match), both poses of nodes and of submaps are to be optimized.
00061 // All constraints are between a submap i and a node j.
00062 class PoseGraph3D : public PoseGraph {
00063  public:
00064   PoseGraph3D(
00065       const proto::PoseGraphOptions& options,
00066       std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem,
00067       common::ThreadPool* thread_pool);
00068   ~PoseGraph3D() override;
00069 
00070   PoseGraph3D(const PoseGraph3D&) = delete;
00071   PoseGraph3D& operator=(const PoseGraph3D&) = delete;
00072 
00073   // Adds a new node with 'constant_data'. Its 'constant_data->local_pose' was
00074   // determined by scan matching against 'insertion_submaps.front()' and the
00075   // node data was inserted into the 'insertion_submaps'. If
00076   // 'insertion_submaps.front().finished()' is 'true', data was inserted into
00077   // this submap for the last time.
00078   NodeId AddNode(
00079       std::shared_ptr<const TrajectoryNode::Data> constant_data,
00080       int trajectory_id,
00081       const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps)
00082       LOCKS_EXCLUDED(mutex_);
00083 
00084   void AddImuData(int trajectory_id, const sensor::ImuData& imu_data) override
00085       LOCKS_EXCLUDED(mutex_);
00086   void AddOdometryData(int trajectory_id,
00087                        const sensor::OdometryData& odometry_data) override
00088       LOCKS_EXCLUDED(mutex_);
00089   void AddFixedFramePoseData(
00090       int trajectory_id,
00091       const sensor::FixedFramePoseData& fixed_frame_pose_data) override
00092       LOCKS_EXCLUDED(mutex_);
00093   void AddLandmarkData(int trajectory_id,
00094                        const sensor::LandmarkData& landmark_data) override
00095       LOCKS_EXCLUDED(mutex_);
00096 
00097   void DeleteTrajectory(int trajectory_id) override;
00098   void FinishTrajectory(int trajectory_id) override;
00099   bool IsTrajectoryFinished(int trajectory_id) const override
00100       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00101   void FreezeTrajectory(int trajectory_id) override;
00102   bool IsTrajectoryFrozen(int trajectory_id) const override
00103       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00104   void AddSubmapFromProto(const transform::Rigid3d& global_submap_pose,
00105                           const proto::Submap& submap) override;
00106   void AddNodeFromProto(const transform::Rigid3d& global_pose,
00107                         const proto::Node& node) override;
00108   void SetTrajectoryDataFromProto(const proto::TrajectoryData& data) override;
00109   void AddNodeToSubmap(const NodeId& node_id,
00110                        const SubmapId& submap_id) override;
00111   void AddSerializedConstraints(
00112       const std::vector<Constraint>& constraints) override;
00113   void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) override;
00114   void RunFinalOptimization() override;
00115   std::vector<std::vector<int>> GetConnectedTrajectories() const override
00116       LOCKS_EXCLUDED(mutex_);
00117   PoseGraph::SubmapData GetSubmapData(const SubmapId& submap_id) const
00118       LOCKS_EXCLUDED(mutex_) override;
00119   MapById<SubmapId, SubmapData> GetAllSubmapData() const
00120       LOCKS_EXCLUDED(mutex_) override;
00121   MapById<SubmapId, SubmapPose> GetAllSubmapPoses() const
00122       LOCKS_EXCLUDED(mutex_) override;
00123   transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const
00124       LOCKS_EXCLUDED(mutex_) override;
00125   MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const override
00126       LOCKS_EXCLUDED(mutex_);
00127   MapById<NodeId, TrajectoryNodePose> GetTrajectoryNodePoses() const override
00128       LOCKS_EXCLUDED(mutex_);
00129   std::map<int, TrajectoryState> GetTrajectoryStates() const override
00130       LOCKS_EXCLUDED(mutex_);
00131   std::map<std::string, transform::Rigid3d> GetLandmarkPoses() const override
00132       LOCKS_EXCLUDED(mutex_);
00133   void SetLandmarkPose(const std::string& landmark_id,
00134                        const transform::Rigid3d& global_pose,
00135                        const bool frozen = false) override
00136       LOCKS_EXCLUDED(mutex_);
00137   sensor::MapByTime<sensor::ImuData> GetImuData() const override
00138       LOCKS_EXCLUDED(mutex_);
00139   sensor::MapByTime<sensor::OdometryData> GetOdometryData() const override
00140       LOCKS_EXCLUDED(mutex_);
00141   sensor::MapByTime<sensor::FixedFramePoseData> GetFixedFramePoseData()
00142       const override LOCKS_EXCLUDED(mutex_);
00143   std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
00144   GetLandmarkNodes() const override LOCKS_EXCLUDED(mutex_);
00145   std::map<int, TrajectoryData> GetTrajectoryData() const override;
00146 
00147   std::vector<Constraint> constraints() const override LOCKS_EXCLUDED(mutex_);
00148   void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id,
00149                                 const transform::Rigid3d& pose,
00150                                 const common::Time time) override
00151       LOCKS_EXCLUDED(mutex_);
00152   void SetGlobalSlamOptimizationCallback(
00153       PoseGraphInterface::GlobalSlamOptimizationCallback callback) override;
00154   transform::Rigid3d GetInterpolatedGlobalTrajectoryPose(
00155       int trajectory_id, const common::Time time) const
00156       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00157 
00158   static void RegisterMetrics(metrics::FamilyFactory* family_factory);
00159 
00160  protected:
00161   // Waits until we caught up (i.e. nothing is waiting to be scheduled), and
00162   // all computations have finished.
00163   void WaitForAllComputations() LOCKS_EXCLUDED(mutex_)
00164       LOCKS_EXCLUDED(work_queue_mutex_);
00165 
00166  private:
00167   MapById<SubmapId, SubmapData> GetSubmapDataUnderLock() const
00168       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00169 
00170   // Handles a new work item.
00171   void AddWorkItem(const std::function<WorkItem::Result()>& work_item)
00172       LOCKS_EXCLUDED(mutex_) LOCKS_EXCLUDED(work_queue_mutex_);
00173 
00174   // Adds connectivity and sampler for a trajectory if it does not exist.
00175   void AddTrajectoryIfNeeded(int trajectory_id)
00176       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00177 
00178   // Appends the new node and submap (if needed) to the internal data stuctures.
00179   NodeId AppendNode(
00180       std::shared_ptr<const TrajectoryNode::Data> constant_data,
00181       int trajectory_id,
00182       const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps,
00183       const transform::Rigid3d& optimized_pose) LOCKS_EXCLUDED(mutex_);
00184 
00185   // Grows the optimization problem to have an entry for every element of
00186   // 'insertion_submaps'. Returns the IDs for the 'insertion_submaps'.
00187   std::vector<SubmapId> InitializeGlobalSubmapPoses(
00188       int trajectory_id, const common::Time time,
00189       const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps)
00190       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00191 
00192   // Adds constraints for a node, and starts scan matching in the background.
00193   WorkItem::Result ComputeConstraintsForNode(
00194       const NodeId& node_id,
00195       std::vector<std::shared_ptr<const Submap3D>> insertion_submaps,
00196       bool newly_finished_submap) LOCKS_EXCLUDED(mutex_);
00197 
00198   // Computes constraints for a node and submap pair.
00199   void ComputeConstraint(const NodeId& node_id, const SubmapId& submap_id)
00200       LOCKS_EXCLUDED(mutex_);
00201 
00202   // Deletes trajectories waiting for deletion. Must not be called during
00203   // constraint search.
00204   void DeleteTrajectoriesIfNeeded() EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00205 
00206   // Runs the optimization, executes the trimmers and processes the work queue.
00207   void HandleWorkQueue(const constraints::ConstraintBuilder3D::Result& result)
00208       LOCKS_EXCLUDED(mutex_) LOCKS_EXCLUDED(work_queue_mutex_);
00209 
00210   // Process pending tasks in the work queue on the calling thread, until the
00211   // queue is either empty or an optimization is required.
00212   void DrainWorkQueue() LOCKS_EXCLUDED(mutex_)
00213       LOCKS_EXCLUDED(work_queue_mutex_);
00214 
00215   // Runs the optimization. Callers have to make sure, that there is only one
00216   // optimization being run at a time.
00217   void RunOptimization() LOCKS_EXCLUDED(mutex_);
00218 
00219   bool CanAddWorkItemModifying(int trajectory_id)
00220       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00221 
00222   // Computes the local to global map frame transform based on the given
00223   // 'global_submap_poses'.
00224   transform::Rigid3d ComputeLocalToGlobalTransform(
00225       const MapById<SubmapId, optimization::SubmapSpec3D>& global_submap_poses,
00226       int trajectory_id) const EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00227 
00228   PoseGraph::SubmapData GetSubmapDataUnderLock(const SubmapId& submap_id) const
00229       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00230 
00231   common::Time GetLatestNodeTime(const NodeId& node_id,
00232                                  const SubmapId& submap_id) const
00233       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00234 
00235   // Logs histograms for the translational and rotational residual of node
00236   // poses.
00237   void LogResidualHistograms() const EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00238 
00239   // Updates the trajectory connectivity structure with a new constraint.
00240   void UpdateTrajectoryConnectivity(const Constraint& constraint)
00241       EXCLUSIVE_LOCKS_REQUIRED(mutex_);
00242 
00243   const proto::PoseGraphOptions options_;
00244   GlobalSlamOptimizationCallback global_slam_optimization_callback_;
00245   mutable absl::Mutex mutex_;
00246   absl::Mutex work_queue_mutex_;
00247 
00248   // If it exists, further work items must be added to this queue, and will be
00249   // considered later.
00250   std::unique_ptr<WorkQueue> work_queue_ GUARDED_BY(work_queue_mutex_);
00251 
00252   // We globally localize a fraction of the nodes from each trajectory.
00253   absl::flat_hash_map<int, std::unique_ptr<common::FixedRatioSampler>>
00254       global_localization_samplers_ GUARDED_BY(mutex_);
00255 
00256   // Number of nodes added since last loop closure.
00257   int num_nodes_since_last_loop_closure_ GUARDED_BY(mutex_) = 0;
00258 
00259   // Current optimization problem.
00260   std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem_;
00261   constraints::ConstraintBuilder3D constraint_builder_;
00262 
00263   // Thread pool used for handling the work queue.
00264   common::ThreadPool* const thread_pool_;
00265 
00266   // List of all trimmers to consult when optimizations finish.
00267   std::vector<std::unique_ptr<PoseGraphTrimmer>> trimmers_ GUARDED_BY(mutex_);
00268 
00269   PoseGraphData data_ GUARDED_BY(mutex_);
00270 
00271   // Allows querying and manipulating the pose graph by the 'trimmers_'. The
00272   // 'mutex_' of the pose graph is held while this class is used.
00273   class TrimmingHandle : public Trimmable {
00274    public:
00275     TrimmingHandle(PoseGraph3D* parent);
00276     ~TrimmingHandle() override {}
00277 
00278     int num_submaps(int trajectory_id) const override;
00279     std::vector<SubmapId> GetSubmapIds(int trajectory_id) const override;
00280     MapById<SubmapId, SubmapData> GetOptimizedSubmapData() const override
00281         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_);
00282     const MapById<NodeId, TrajectoryNode>& GetTrajectoryNodes() const override
00283         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_);
00284     const std::vector<Constraint>& GetConstraints() const override
00285         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_);
00286     void TrimSubmap(const SubmapId& submap_id)
00287         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_) override;
00288     bool IsFinished(int trajectory_id) const override
00289         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_);
00290 
00291     void SetTrajectoryState(int trajectory_id, TrajectoryState state) override
00292         EXCLUSIVE_LOCKS_REQUIRED(parent_->mutex_);
00293 
00294    private:
00295     PoseGraph3D* const parent_;
00296   };
00297 };
00298 
00299 }  // namespace mapping
00300 }  // namespace cartographer
00301 
00302 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_


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