map_builder.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_MAP_BUILDER_H_
00018 #define CARTOGRAPHER_MAPPING_MAP_BUILDER_H_
00019 
00020 #include <memory>
00021 
00022 #include "cartographer/common/thread_pool.h"
00023 #include "cartographer/mapping/map_builder_interface.h"
00024 #include "cartographer/mapping/pose_graph.h"
00025 #include "cartographer/mapping/proto/map_builder_options.pb.h"
00026 #include "cartographer/sensor/collator_interface.h"
00027 
00028 namespace cartographer {
00029 namespace mapping {
00030 
00031 proto::MapBuilderOptions CreateMapBuilderOptions(
00032     common::LuaParameterDictionary *const parameter_dictionary);
00033 
00034 // Wires up the complete SLAM stack with TrajectoryBuilders (for local submaps)
00035 // and a PoseGraph for loop closure.
00036 class MapBuilder : public MapBuilderInterface {
00037  public:
00038   explicit MapBuilder(const proto::MapBuilderOptions &options);
00039   ~MapBuilder() override {}
00040 
00041   MapBuilder(const MapBuilder &) = delete;
00042   MapBuilder &operator=(const MapBuilder &) = delete;
00043 
00044   int AddTrajectoryBuilder(
00045       const std::set<SensorId> &expected_sensor_ids,
00046       const proto::TrajectoryBuilderOptions &trajectory_options,
00047       LocalSlamResultCallback local_slam_result_callback) override;
00048 
00049   int AddTrajectoryForDeserialization(
00050       const proto::TrajectoryBuilderOptionsWithSensorIds
00051           &options_with_sensor_ids_proto) override;
00052 
00053   void FinishTrajectory(int trajectory_id) override;
00054 
00055   std::string SubmapToProto(const SubmapId &submap_id,
00056                             proto::SubmapQuery::Response *response) override;
00057 
00058   void SerializeState(bool include_unfinished_submaps,
00059                       io::ProtoStreamWriterInterface *writer) override;
00060 
00061   bool SerializeStateToFile(bool include_unfinished_submaps,
00062                             const std::string &filename) override;
00063 
00064   std::map<int, int> LoadState(io::ProtoStreamReaderInterface *reader,
00065                                bool load_frozen_state) override;
00066 
00067   std::map<int, int> LoadStateFromFile(const std::string &filename,
00068                                        const bool load_frozen_state) override;
00069 
00070   mapping::PoseGraphInterface *pose_graph() override {
00071     return pose_graph_.get();
00072   }
00073 
00074   int num_trajectory_builders() const override {
00075     return trajectory_builders_.size();
00076   }
00077 
00078   mapping::TrajectoryBuilderInterface *GetTrajectoryBuilder(
00079       int trajectory_id) const override {
00080     return trajectory_builders_.at(trajectory_id).get();
00081   }
00082 
00083   const std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>
00084       &GetAllTrajectoryBuilderOptions() const override {
00085     return all_trajectory_builder_options_;
00086   }
00087 
00088  private:
00089   const proto::MapBuilderOptions options_;
00090   common::ThreadPool thread_pool_;
00091 
00092   std::unique_ptr<PoseGraph> pose_graph_;
00093 
00094   std::unique_ptr<sensor::CollatorInterface> sensor_collator_;
00095   std::vector<std::unique_ptr<mapping::TrajectoryBuilderInterface>>
00096       trajectory_builders_;
00097   std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>
00098       all_trajectory_builder_options_;
00099 };
00100 
00101 }  // namespace mapping
00102 }  // namespace cartographer
00103 
00104 #endif  // CARTOGRAPHER_MAPPING_MAP_BUILDER_H_


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