pose_graph_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 
17 #ifndef CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_
18 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_
19 
20 #include <vector>
21 
26 
27 namespace cartographer {
28 namespace mapping {
29 
31  public:
32  // A "constraint" as in the paper by Konolige, Kurt, et al. "Efficient sparse
33  // pose adjustment for 2d mapping." Intelligent Robots and Systems (IROS),
34  // 2010 IEEE/RSJ International Conference on (pp. 22--29). IEEE, 2010.
35  struct Constraint {
36  struct Pose {
40  };
41 
42  SubmapId submap_id; // 'i' in the paper.
43  NodeId node_id; // 'j' in the paper.
44 
45  // Pose of the node 'j' relative to submap 'i'.
47 
48  // Differentiates between intra-submap (where node 'j' was inserted into
49  // submap 'i') and inter-submap constraints (where node 'j' was not inserted
50  // into submap 'i').
52  };
53 
54  struct LandmarkNode {
61  };
62  std::vector<LandmarkObservation> landmark_observations;
64  };
65 
66  struct SubmapPose {
67  int version;
69  };
70 
71  struct SubmapData {
72  std::shared_ptr<const Submap> submap;
74  };
75 
76  struct TrajectoryData {
77  double gravity_constant = 9.8;
78  std::array<double, 4> imu_calibration{{1., 0., 0., 0.}};
80  };
81 
83  std::function<void(const std::map<int /* trajectory_id */, SubmapId>&,
84  const std::map<int /* trajectory_id */, NodeId>&)>;
85 
87  virtual ~PoseGraphInterface() {}
88 
89  PoseGraphInterface(const PoseGraphInterface&) = delete;
91 
92  // Waits for all computations to finish and computes optimized poses.
93  virtual void RunFinalOptimization() = 0;
94 
95  // Returns data for all submaps.
97 
98  // Returns the global poses for all submaps.
100 
101  // Returns the transform converting data in the local map frame (i.e. the
102  // continuous, non-loop-closed frame) into the global map frame (i.e. the
103  // discontinuous, loop-closed frame).
105  int trajectory_id) const = 0;
106 
107  // Returns the current optimized trajectories.
109 
110  // Returns the current optimized trajectory poses.
112  const = 0;
113 
114  // Returns the current optimized landmark poses.
115  virtual std::map<std::string, transform::Rigid3d> GetLandmarkPoses()
116  const = 0;
117 
118  // Sets global pose of landmark 'landmark_id' to given 'global_pose'.
119  virtual void SetLandmarkPose(const std::string& landmark_id,
120  const transform::Rigid3d& global_pose) = 0;
121 
122  // Checks if the given trajectory is finished.
123  virtual bool IsTrajectoryFinished(int trajectory_id) const = 0;
124 
125  // Checks if the given trajectory is frozen.
126  virtual bool IsTrajectoryFrozen(int trajectory_id) const = 0;
127 
128  // Returns the trajectory data.
129  virtual std::map<int, TrajectoryData> GetTrajectoryData() const = 0;
130 
131  // Returns the collection of constraints.
132  virtual std::vector<Constraint> constraints() const = 0;
133 
134  // Serializes the constraints and trajectories.
135  virtual proto::PoseGraph ToProto() const = 0;
136 
137  // Sets the callback function that is invoked whenever the global optimization
138  // problem is solved.
140  GlobalSlamOptimizationCallback callback) = 0;
141 };
142 
143 } // namespace mapping
144 } // namespace cartographer
145 
146 #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_
virtual void SetGlobalSlamOptimizationCallback(GlobalSlamOptimizationCallback callback)=0
enum cartographer::mapping::PoseGraphInterface::Constraint::Tag tag
common::optional< transform::Rigid3d > global_landmark_pose
virtual bool IsTrajectoryFinished(int trajectory_id) const =0
common::optional< transform::Rigid3d > fixed_frame_origin_in_map
virtual void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose)=0
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
virtual std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const =0
virtual transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const =0
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
virtual proto::PoseGraph ToProto() const =0
virtual MapById< NodeId, TrajectoryNodePose > GetTrajectoryNodePoses() const =0
PoseGraphInterface & operator=(const PoseGraphInterface &)=delete
virtual std::map< int, TrajectoryData > GetTrajectoryData() const =0
virtual std::vector< Constraint > constraints() const =0
virtual MapById< SubmapId, SubmapData > GetAllSubmapData() const =0
virtual MapById< SubmapId, SubmapPose > GetAllSubmapPoses() const =0
virtual MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const =0
virtual bool IsTrajectoryFrozen(int trajectory_id) const =0


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