Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
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
00034
00035
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;
00044 NodeId node_id;
00045
00046
00047 Pose pose;
00048
00049
00050
00051
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
00097 virtual void RunFinalOptimization() = 0;
00098
00099
00100 virtual MapById<SubmapId, SubmapData> GetAllSubmapData() const = 0;
00101
00102
00103 virtual MapById<SubmapId, SubmapPose> GetAllSubmapPoses() const = 0;
00104
00105
00106
00107
00108 virtual transform::Rigid3d GetLocalToGlobalTransform(
00109 int trajectory_id) const = 0;
00110
00111
00112 virtual MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const = 0;
00113
00114
00115 virtual MapById<NodeId, TrajectoryNodePose> GetTrajectoryNodePoses()
00116 const = 0;
00117
00118
00119 virtual std::map<int, TrajectoryState> GetTrajectoryStates() const = 0;
00120
00121
00122 virtual std::map<std::string, transform::Rigid3d> GetLandmarkPoses()
00123 const = 0;
00124
00125
00126 virtual void SetLandmarkPose(const std::string& landmark_id,
00127 const transform::Rigid3d& global_pose,
00128 const bool frozen = false) = 0;
00129
00130
00131 virtual void DeleteTrajectory(int trajectory_id) = 0;
00132
00133
00134 virtual bool IsTrajectoryFinished(int trajectory_id) const = 0;
00135
00136
00137 virtual bool IsTrajectoryFrozen(int trajectory_id) const = 0;
00138
00139
00140 virtual std::map<int, TrajectoryData> GetTrajectoryData() const = 0;
00141
00142
00143 virtual std::vector<Constraint> constraints() const = 0;
00144
00145
00146
00147
00148
00149 virtual proto::PoseGraph ToProto(bool include_unfinished_submaps) const = 0;
00150
00151
00152
00153 virtual void SetGlobalSlamOptimizationCallback(
00154 GlobalSlamOptimizationCallback callback) = 0;
00155 };
00156
00157 }
00158 }
00159
00160 #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_INTERFACE_H_