map_builder.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_MAP_BUILDER_H_
18 #define CARTOGRAPHER_MAPPING_MAP_BUILDER_H_
19 
21 
22 #include <memory>
23 
26 #include "cartographer/mapping/proto/map_builder_options.pb.h"
28 
29 namespace cartographer {
30 namespace mapping {
31 
32 proto::MapBuilderOptions CreateMapBuilderOptions(
33  common::LuaParameterDictionary *const parameter_dictionary);
34 
35 // Wires up the complete SLAM stack with TrajectoryBuilders (for local submaps)
36 // and a PoseGraph for loop closure.
38  public:
39  explicit MapBuilder(const proto::MapBuilderOptions &options);
40  ~MapBuilder() override {}
41 
42  MapBuilder(const MapBuilder &) = delete;
43  MapBuilder &operator=(const MapBuilder &) = delete;
44 
46  const std::set<SensorId> &expected_sensor_ids,
47  const proto::TrajectoryBuilderOptions &trajectory_options,
48  LocalSlamResultCallback local_slam_result_callback) override;
49 
51  const proto::TrajectoryBuilderOptionsWithSensorIds
52  &options_with_sensor_ids_proto) override;
53 
54  void FinishTrajectory(int trajectory_id) override;
55 
56  std::string SubmapToProto(const SubmapId &submap_id,
57  proto::SubmapQuery::Response *response) override;
58 
59  void SerializeState(io::ProtoStreamWriterInterface *writer) override;
60 
62  bool load_frozen_state) override;
63 
65  return pose_graph_.get();
66  }
67 
68  int num_trajectory_builders() const override {
69  return trajectory_builders_.size();
70  }
71 
73  int trajectory_id) const override {
74  return trajectory_builders_.at(trajectory_id).get();
75  }
76 
77  const std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>
78  &GetAllTrajectoryBuilderOptions() const override {
80  }
81 
82  private:
83  const proto::MapBuilderOptions options_;
85 
86  std::unique_ptr<PoseGraph> pose_graph_;
87 
88  std::unique_ptr<sensor::CollatorInterface> sensor_collator_;
89  std::vector<std::unique_ptr<mapping::TrajectoryBuilderInterface>>
91  std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>
93 };
94 
95 } // namespace mapping
96 } // namespace cartographer
97 
98 #endif // CARTOGRAPHER_MAPPING_MAP_BUILDER_H_
void SerializeState(io::ProtoStreamWriterInterface *writer) override
Definition: map_builder.cc:205
void FinishTrajectory(int trajectory_id) override
Definition: map_builder.cc:181
std::vector< proto::TrajectoryBuilderOptionsWithSensorIds > all_trajectory_builder_options_
Definition: map_builder.h:92
TrajectoryBuilderInterface::LocalSlamResultCallback LocalSlamResultCallback
mapping::TrajectoryBuilderInterface * GetTrajectoryBuilder(int trajectory_id) const override
Definition: map_builder.h:72
int num_trajectory_builders() const override
Definition: map_builder.h:68
std::string SubmapToProto(const SubmapId &submap_id, proto::SubmapQuery::Response *response) override
Definition: map_builder.cc:186
const std::vector< proto::TrajectoryBuilderOptionsWithSensorIds > & GetAllTrajectoryBuilderOptions() const override
Definition: map_builder.h:78
proto::MapBuilderOptions CreateMapBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
Definition: map_builder.cc:57
const proto::MapBuilderOptions options_
Definition: map_builder.h:83
void LoadState(io::ProtoStreamReaderInterface *reader, bool load_frozen_state) override
Definition: map_builder.cc:209
std::unique_ptr< PoseGraph > pose_graph_
Definition: map_builder.h:86
std::vector< std::unique_ptr< mapping::TrajectoryBuilderInterface > > trajectory_builders_
Definition: map_builder.h:90
std::unique_ptr< sensor::CollatorInterface > sensor_collator_
Definition: map_builder.h:88
common::ThreadPool thread_pool_
Definition: map_builder.h:84
int AddTrajectoryBuilder(const std::set< SensorId > &expected_sensor_ids, const proto::TrajectoryBuilderOptions &trajectory_options, LocalSlamResultCallback local_slam_result_callback) override
Definition: map_builder.cc:98
int AddTrajectoryForDeserialization(const proto::TrajectoryBuilderOptionsWithSensorIds &options_with_sensor_ids_proto) override
Definition: map_builder.cc:171
MapBuilder(const proto::MapBuilderOptions &options)
Definition: map_builder.cc:73
mapping::PoseGraphInterface * pose_graph() override
Definition: map_builder.h:64
MapBuilder & operator=(const MapBuilder &)=delete


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