pose_graph_interface.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_POSE_GRAPH_INTERFACE_H_
00018 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_
00019 
00020 #include <chrono>
00021 #include <vector>
00022 
00023 #include "absl/types/optional.h"
00024 #include "cartographer/mapping/id.h"
00025 #include "cartographer/mapping/submaps.h"
00026 #include "cartographer/transform/rigid_transform.h"
00027 
00028 namespace cartographer {
00029 namespace mapping {
00030 
00031 class PoseGraphInterface {
00032  public:
00033   // A "constraint" as in the paper by Konolige, Kurt, et al. "Efficient sparse
00034   // pose adjustment for 2d mapping." Intelligent Robots and Systems (IROS),
00035   // 2010 IEEE/RSJ International Conference on (pp. 22--29). IEEE, 2010.
00036   struct Constraint {
00037     struct Pose {
00038       transform::Rigid3d zbar_ij;
00039       double translation_weight;
00040       double rotation_weight;
00041     };
00042 
00043     SubmapId submap_id;  // 'i' in the paper.
00044     NodeId node_id;      // 'j' in the paper.
00045 
00046     // Pose of the node 'j' relative to submap 'i'.
00047     Pose pose;
00048 
00049     // Differentiates between intra-submap (where node 'j' was inserted into
00050     // submap 'i') and inter-submap constraints (where node 'j' was not inserted
00051     // into submap 'i').
00052     enum Tag { INTRA_SUBMAP, INTER_SUBMAP } tag;
00053   };
00054 
00055   struct LandmarkNode {
00056     struct LandmarkObservation {
00057       int trajectory_id;
00058       common::Time time;
00059       transform::Rigid3d landmark_to_tracking_transform;
00060       double translation_weight;
00061       double rotation_weight;
00062     };
00063     std::vector<LandmarkObservation> landmark_observations;
00064     absl::optional<transform::Rigid3d> global_landmark_pose;
00065     bool frozen = false;
00066   };
00067 
00068   struct SubmapPose {
00069     int version;
00070     transform::Rigid3d pose;
00071   };
00072 
00073   struct SubmapData {
00074     std::shared_ptr<const Submap> submap;
00075     transform::Rigid3d pose;
00076   };
00077 
00078   struct TrajectoryData {
00079     double gravity_constant = 9.8;
00080     std::array<double, 4> imu_calibration{{1., 0., 0., 0.}};
00081     absl::optional<transform::Rigid3d> fixed_frame_origin_in_map;
00082   };
00083 
00084   enum class TrajectoryState { ACTIVE, FINISHED, FROZEN, DELETED };
00085 
00086   using GlobalSlamOptimizationCallback =
00087       std::function<void(const std::map<int /* trajectory_id */, SubmapId>&,
00088                          const std::map<int /* trajectory_id */, NodeId>&)>;
00089 
00090   PoseGraphInterface() {}
00091   virtual ~PoseGraphInterface() {}
00092 
00093   PoseGraphInterface(const PoseGraphInterface&) = delete;
00094   PoseGraphInterface& operator=(const PoseGraphInterface&) = delete;
00095 
00096   // Waits for all computations to finish and computes optimized poses.
00097   virtual void RunFinalOptimization() = 0;
00098 
00099   // Returns data for all submaps.
00100   virtual MapById<SubmapId, SubmapData> GetAllSubmapData() const = 0;
00101 
00102   // Returns the global poses for all submaps.
00103   virtual MapById<SubmapId, SubmapPose> GetAllSubmapPoses() const = 0;
00104 
00105   // Returns the transform converting data in the local map frame (i.e. the
00106   // continuous, non-loop-closed frame) into the global map frame (i.e. the
00107   // discontinuous, loop-closed frame).
00108   virtual transform::Rigid3d GetLocalToGlobalTransform(
00109       int trajectory_id) const = 0;
00110 
00111   // Returns the current optimized trajectories.
00112   virtual MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const = 0;
00113 
00114   // Returns the current optimized trajectory poses.
00115   virtual MapById<NodeId, TrajectoryNodePose> GetTrajectoryNodePoses()
00116       const = 0;
00117 
00118   // Returns the states of trajectories.
00119   virtual std::map<int, TrajectoryState> GetTrajectoryStates() const = 0;
00120 
00121   // Returns the current optimized landmark poses.
00122   virtual std::map<std::string, transform::Rigid3d> GetLandmarkPoses()
00123       const = 0;
00124 
00125   // Sets global pose of landmark 'landmark_id' to given 'global_pose'.
00126   virtual void SetLandmarkPose(const std::string& landmark_id,
00127                                const transform::Rigid3d& global_pose,
00128                                const bool frozen = false) = 0;
00129 
00130   // Deletes a trajectory asynchronously.
00131   virtual void DeleteTrajectory(int trajectory_id) = 0;
00132 
00133   // Checks if the given trajectory is finished.
00134   virtual bool IsTrajectoryFinished(int trajectory_id) const = 0;
00135 
00136   // Checks if the given trajectory is frozen.
00137   virtual bool IsTrajectoryFrozen(int trajectory_id) const = 0;
00138 
00139   // Returns the trajectory data.
00140   virtual std::map<int, TrajectoryData> GetTrajectoryData() const = 0;
00141 
00142   // Returns the collection of constraints.
00143   virtual std::vector<Constraint> constraints() const = 0;
00144 
00145   // Serializes the constraints and trajectories. If
00146   // 'include_unfinished_submaps' is set to 'true', unfinished submaps, i.e.
00147   // submaps that have not yet received all rangefinder data insertions, will
00148   // be included, otherwise not.
00149   virtual proto::PoseGraph ToProto(bool include_unfinished_submaps) const = 0;
00150 
00151   // Sets the callback function that is invoked whenever the global optimization
00152   // problem is solved.
00153   virtual void SetGlobalSlamOptimizationCallback(
00154       GlobalSlamOptimizationCallback callback) = 0;
00155 };
00156 
00157 }  // namespace mapping
00158 }  // namespace cartographer
00159 
00160 #endif  // CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_


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