map_builder_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 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_INTERFACE_H_
18 #define CARTOGRAPHER_MAPPING_MAP_BUILDER_INTERFACE_H_
19 
20 #include <set>
21 #include <string>
22 #include <vector>
23 
24 #include "Eigen/Geometry"
30 #include "cartographer/mapping/proto/submap_visualization.pb.h"
31 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
34 
35 namespace cartographer {
36 namespace mapping {
37 
38 // This interface is used for both library and RPC implementations.
39 // Implementations wire up the complete SLAM stack.
41  public:
44 
46 
48  virtual ~MapBuilderInterface() {}
49 
52 
53  // Creates a new trajectory builder and returns its index.
54  virtual int AddTrajectoryBuilder(
55  const std::set<SensorId>& expected_sensor_ids,
56  const proto::TrajectoryBuilderOptions& trajectory_options,
57  LocalSlamResultCallback local_slam_result_callback) = 0;
58 
59  // Creates a new trajectory and returns its index. Querying the trajectory
60  // builder for it will return 'nullptr'.
62  const proto::TrajectoryBuilderOptionsWithSensorIds&
63  options_with_sensor_ids_proto) = 0;
64 
65  // Returns the 'TrajectoryBuilderInterface' corresponding to the specified
66  // 'trajectory_id' or 'nullptr' if the trajectory has no corresponding
67  // builder.
69  int trajectory_id) const = 0;
70 
71  // Marks the TrajectoryBuilder corresponding to 'trajectory_id' as finished,
72  // i.e. no further sensor data is expected.
73  virtual void FinishTrajectory(int trajectory_id) = 0;
74 
75  // Fills the SubmapQuery::Response corresponding to 'submap_id'. Returns an
76  // error string on failure, or an empty string on success.
77  virtual std::string SubmapToProto(const SubmapId& submap_id,
78  proto::SubmapQuery::Response* response) = 0;
79 
80  // Serializes the current state to a proto stream.
81  virtual void SerializeState(io::ProtoStreamWriterInterface* writer) = 0;
82 
83  // Loads the SLAM state from a proto stream.
84  virtual void LoadState(io::ProtoStreamReaderInterface* reader,
85  bool load_frozen_state) = 0;
86 
87  virtual int num_trajectory_builders() const = 0;
88 
90 
91  virtual const std::vector<proto::TrajectoryBuilderOptionsWithSensorIds>&
93 };
94 
95 } // namespace mapping
96 } // namespace cartographer
97 
98 #endif // CARTOGRAPHER_MAPPING_MAP_BUILDER_INTERFACE_H_
TrajectoryBuilderInterface::LocalSlamResultCallback LocalSlamResultCallback
virtual std::string SubmapToProto(const SubmapId &submap_id, proto::SubmapQuery::Response *response)=0
virtual void FinishTrajectory(int trajectory_id)=0
virtual void LoadState(io::ProtoStreamReaderInterface *reader, bool load_frozen_state)=0
virtual int AddTrajectoryBuilder(const std::set< SensorId > &expected_sensor_ids, const proto::TrajectoryBuilderOptions &trajectory_options, LocalSlamResultCallback local_slam_result_callback)=0
virtual const std::vector< proto::TrajectoryBuilderOptionsWithSensorIds > & GetAllTrajectoryBuilderOptions() const =0
virtual mapping::PoseGraphInterface * pose_graph()=0
virtual int num_trajectory_builders() const =0
virtual int AddTrajectoryForDeserialization(const proto::TrajectoryBuilderOptionsWithSensorIds &options_with_sensor_ids_proto)=0
virtual void SerializeState(io::ProtoStreamWriterInterface *writer)=0
virtual mapping::TrajectoryBuilderInterface * GetTrajectoryBuilder(int trajectory_id) const =0
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback
MapBuilderInterface & operator=(const MapBuilderInterface &)=delete


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