pose_graph.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_H_
00018 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_H_
00019 
00020 #include <memory>
00021 #include <set>
00022 #include <utility>
00023 #include <vector>
00024 
00025 #include "absl/container/flat_hash_map.h"
00026 #include "cartographer/common/lua_parameter_dictionary.h"
00027 #include "cartographer/mapping/id.h"
00028 #include "cartographer/mapping/pose_graph_interface.h"
00029 #include "cartographer/mapping/pose_graph_trimmer.h"
00030 #include "cartographer/mapping/proto/pose_graph.pb.h"
00031 #include "cartographer/mapping/proto/pose_graph_options.pb.h"
00032 #include "cartographer/mapping/proto/serialization.pb.h"
00033 #include "cartographer/mapping/submaps.h"
00034 #include "cartographer/mapping/trajectory_node.h"
00035 #include "cartographer/sensor/fixed_frame_pose_data.h"
00036 #include "cartographer/sensor/imu_data.h"
00037 #include "cartographer/sensor/landmark_data.h"
00038 #include "cartographer/sensor/map_by_time.h"
00039 #include "cartographer/sensor/odometry_data.h"
00040 
00041 namespace cartographer {
00042 namespace mapping {
00043 
00044 proto::PoseGraphOptions CreatePoseGraphOptions(
00045     common::LuaParameterDictionary* const parameter_dictionary);
00046 
00047 class PoseGraph : public PoseGraphInterface {
00048  public:
00049   struct InitialTrajectoryPose {
00050     int to_trajectory_id;
00051     transform::Rigid3d relative_pose;
00052     common::Time time;
00053   };
00054 
00055   PoseGraph() {}
00056   ~PoseGraph() override {}
00057 
00058   PoseGraph(const PoseGraph&) = delete;
00059   PoseGraph& operator=(const PoseGraph&) = delete;
00060 
00061   // Inserts an IMU measurement.
00062   virtual void AddImuData(int trajectory_id,
00063                           const sensor::ImuData& imu_data) = 0;
00064 
00065   // Inserts an odometry measurement.
00066   virtual void AddOdometryData(int trajectory_id,
00067                                const sensor::OdometryData& odometry_data) = 0;
00068 
00069   // Inserts a fixed frame pose measurement.
00070   virtual void AddFixedFramePoseData(
00071       int trajectory_id,
00072       const sensor::FixedFramePoseData& fixed_frame_pose_data) = 0;
00073 
00074   // Inserts landmarks observations.
00075   virtual void AddLandmarkData(int trajectory_id,
00076                                const sensor::LandmarkData& landmark_data) = 0;
00077 
00078   // Finishes the given trajectory.
00079   virtual void FinishTrajectory(int trajectory_id) = 0;
00080 
00081   // Freezes a trajectory. Poses in this trajectory will not be optimized.
00082   virtual void FreezeTrajectory(int trajectory_id) = 0;
00083 
00084   // Adds a 'submap' from a proto with the given 'global_pose' to the
00085   // appropriate trajectory.
00086   virtual void AddSubmapFromProto(const transform::Rigid3d& global_pose,
00087                                   const proto::Submap& submap) = 0;
00088 
00089   // Adds a 'node' from a proto with the given 'global_pose' to the
00090   // appropriate trajectory.
00091   virtual void AddNodeFromProto(const transform::Rigid3d& global_pose,
00092                                 const proto::Node& node) = 0;
00093 
00094   // Sets the trajectory data from a proto.
00095   virtual void SetTrajectoryDataFromProto(
00096       const mapping::proto::TrajectoryData& data) = 0;
00097 
00098   // Adds information that 'node_id' was inserted into 'submap_id'. The submap
00099   // has to be deserialized first.
00100   virtual void AddNodeToSubmap(const NodeId& node_id,
00101                                const SubmapId& submap_id) = 0;
00102 
00103   // Adds serialized constraints. The corresponding trajectory nodes and submaps
00104   // have to be deserialized before calling this function.
00105   virtual void AddSerializedConstraints(
00106       const std::vector<Constraint>& constraints) = 0;
00107 
00108   // Adds a 'trimmer'. It will be used after all data added before it has been
00109   // included in the pose graph.
00110   virtual void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) = 0;
00111 
00112   // Gets the current trajectory clusters.
00113   virtual std::vector<std::vector<int>> GetConnectedTrajectories() const = 0;
00114 
00115   // Returns the current optimized transform and submap itself for the given
00116   // 'submap_id'. Returns 'nullptr' for the 'submap' member if the submap does
00117   // not exist (anymore).
00118   virtual SubmapData GetSubmapData(const SubmapId& submap_id) const = 0;
00119 
00120   proto::PoseGraph ToProto(bool include_unfinished_submaps) const override;
00121 
00122   // Returns the IMU data.
00123   virtual sensor::MapByTime<sensor::ImuData> GetImuData() const = 0;
00124 
00125   // Returns the odometry data.
00126   virtual sensor::MapByTime<sensor::OdometryData> GetOdometryData() const = 0;
00127 
00128   // Returns the fixed frame pose data.
00129   virtual sensor::MapByTime<sensor::FixedFramePoseData> GetFixedFramePoseData()
00130       const = 0;
00131 
00132   // Returns the landmark data.
00133   virtual std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
00134   GetLandmarkNodes() const = 0;
00135 
00136   // Sets a relative initial pose 'relative_pose' for 'from_trajectory_id' with
00137   // respect to 'to_trajectory_id' at time 'time'.
00138   virtual void SetInitialTrajectoryPose(int from_trajectory_id,
00139                                         int to_trajectory_id,
00140                                         const transform::Rigid3d& pose,
00141                                         const common::Time time) = 0;
00142 };
00143 
00144 std::vector<PoseGraph::Constraint> FromProto(
00145     const ::google::protobuf::RepeatedPtrField<
00146         ::cartographer::mapping::proto::PoseGraph::Constraint>&
00147         constraint_protos);
00148 proto::PoseGraph::Constraint ToProto(const PoseGraph::Constraint& constraint);
00149 
00150 }  // namespace mapping
00151 }  // namespace cartographer
00152 
00153 #endif  // CARTOGRAPHER_MAPPING_POSE_GRAPH_H_


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