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_TRAJECTORY_BUILDER_INTERFACE_H_
00018 #define CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_
00019
00020 #include <functional>
00021 #include <memory>
00022 #include <string>
00023
00024 #include "absl/memory/memory.h"
00025 #include "cartographer/common/lua_parameter_dictionary.h"
00026 #include "cartographer/common/port.h"
00027 #include "cartographer/common/time.h"
00028 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
00029 #include "cartographer/mapping/submaps.h"
00030 #include "cartographer/sensor/fixed_frame_pose_data.h"
00031 #include "cartographer/sensor/imu_data.h"
00032 #include "cartographer/sensor/landmark_data.h"
00033 #include "cartographer/sensor/odometry_data.h"
00034 #include "cartographer/sensor/timed_point_cloud_data.h"
00035
00036 namespace cartographer {
00037 namespace mapping {
00038
00039 proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(
00040 common::LuaParameterDictionary* const parameter_dictionary);
00041
00042 class LocalSlamResultData;
00043
00044
00045
00046
00047
00048 class TrajectoryBuilderInterface {
00049 public:
00050 struct InsertionResult {
00051 NodeId node_id;
00052 std::shared_ptr<const TrajectoryNode::Data> constant_data;
00053 std::vector<std::shared_ptr<const Submap>> insertion_submaps;
00054 };
00055
00056
00057
00058
00059 using LocalSlamResultCallback =
00060 std::function<void(int , common::Time,
00061 transform::Rigid3d ,
00062 sensor::RangeData ,
00063 std::unique_ptr<const InsertionResult>)>;
00064
00065 struct SensorId {
00066 enum class SensorType {
00067 RANGE = 0,
00068 IMU,
00069 ODOMETRY,
00070 FIXED_FRAME_POSE,
00071 LANDMARK,
00072 LOCAL_SLAM_RESULT
00073 };
00074
00075 SensorType type;
00076 std::string id;
00077
00078 bool operator==(const SensorId& other) const {
00079 return std::forward_as_tuple(type, id) ==
00080 std::forward_as_tuple(other.type, other.id);
00081 }
00082
00083 bool operator<(const SensorId& other) const {
00084 return std::forward_as_tuple(type, id) <
00085 std::forward_as_tuple(other.type, other.id);
00086 }
00087 };
00088
00089 TrajectoryBuilderInterface() {}
00090 virtual ~TrajectoryBuilderInterface() {}
00091
00092 TrajectoryBuilderInterface(const TrajectoryBuilderInterface&) = delete;
00093 TrajectoryBuilderInterface& operator=(const TrajectoryBuilderInterface&) =
00094 delete;
00095
00096 virtual void AddSensorData(
00097 const std::string& sensor_id,
00098 const sensor::TimedPointCloudData& timed_point_cloud_data) = 0;
00099 virtual void AddSensorData(const std::string& sensor_id,
00100 const sensor::ImuData& imu_data) = 0;
00101 virtual void AddSensorData(const std::string& sensor_id,
00102 const sensor::OdometryData& odometry_data) = 0;
00103 virtual void AddSensorData(
00104 const std::string& sensor_id,
00105 const sensor::FixedFramePoseData& fixed_frame_pose) = 0;
00106 virtual void AddSensorData(const std::string& sensor_id,
00107 const sensor::LandmarkData& landmark_data) = 0;
00108
00109
00110
00111 virtual void AddLocalSlamResultData(
00112 std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) = 0;
00113 };
00114
00115 proto::SensorId ToProto(const TrajectoryBuilderInterface::SensorId& sensor_id);
00116 TrajectoryBuilderInterface::SensorId FromProto(
00117 const proto::SensorId& sensor_id_proto);
00118
00119 }
00120 }
00121
00122 #endif // CARTOGRAPHER_MAPPING_TRAJECTORY_BUILDER_INTERFACE_H_