17 #ifndef CARTOGRAPHER_MAPPING_3D_SUBMAP_3D_H_ 18 #define CARTOGRAPHER_MAPPING_3D_SUBMAP_3D_H_ 24 #include "Eigen/Geometry" 29 #include "cartographer/mapping/proto/3d/submaps_options_3d.pb.h" 30 #include "cartographer/mapping/proto/serialization.pb.h" 31 #include "cartographer/mapping/proto/submap_visualization.pb.h" 41 common::LuaParameterDictionary* parameter_dictionary);
45 Submap3D(
float high_resolution,
float low_resolution,
47 explicit Submap3D(
const proto::Submap3D& proto);
49 void ToProto(proto::Submap* proto,
50 bool include_probability_grid_data)
const override;
54 proto::SubmapQuery::Response* response)
const override;
67 int high_resolution_max_range);
93 int matching_index()
const;
99 const Eigen::Quaterniond& gravity_alignment);
101 std::vector<std::shared_ptr<Submap3D>> submaps()
const;
107 int matching_submap_index_ = 0;
115 #endif // CARTOGRAPHER_MAPPING_3D_SUBMAP_3D_H_
std::unique_ptr< HybridGrid > high_resolution_hybrid_grid_
void UpdateFromProto(const proto::Submap &proto) override
const proto::SubmapsOptions3D options_
const HybridGrid & high_resolution_hybrid_grid() const
RangeDataInserter3D range_data_inserter_
const HybridGrid & low_resolution_hybrid_grid() const
void ToResponseProto(const transform::Rigid3d &global_submap_pose, proto::SubmapQuery::Response *response) const override
void ToProto(proto::Submap *proto, bool include_probability_grid_data) const override
std::unique_ptr< HybridGrid > low_resolution_hybrid_grid_
void InsertRangeData(const sensor::RangeData &range_data, const RangeDataInserter3D &range_data_inserter, int high_resolution_max_range)
proto::SubmapsOptions3D CreateSubmapsOptions3D(common::LuaParameterDictionary *parameter_dictionary)
std::vector< std::shared_ptr< Submap3D > > submaps_
Submap3D(float high_resolution, float low_resolution, const transform::Rigid3d &local_submap_pose)