map_builder_context_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2018 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_CLOUD_MAP_BUILDER_CONTEXT_INTERFACE_H
18 #define CARTOGRAPHER_CLOUD_MAP_BUILDER_CONTEXT_INTERFACE_H
19 
20 #include "async_grpc/execution_context.h"
25 #include "cartographer/mapping/proto/serialization.pb.h"
29 
30 namespace cartographer {
31 namespace cloud {
32 
33 class MapBuilderServer;
34 class MapBuilderContextInterface : public async_grpc::ExecutionContext {
35  public:
36  struct LocalSlamResult {
40  std::shared_ptr<const sensor::RangeData> range_data;
41  std::unique_ptr<const mapping::TrajectoryBuilderInterface::InsertionResult>
43  };
44  // Calling with 'nullptr' signals subscribers that the subscription has ended,
45  // e.g. this happens when the corresponding trajectory was finished and hence
46  // no more local SLAM updates will occur.
47  // The callback can return 'false' to indicate that the client is not
48  // interested in more local SLAM updates and 'MapBuilderServer' will end the
49  // subscription.
51  std::function<bool(std::unique_ptr<LocalSlamResult>)>;
52 
53  // The callback can return 'false' to indicate that the client is not
54  // interested in more global SLAM runs and 'MapBuilderServer' will end the
55  // subscription.
56  using GlobalSlamOptimizationCallback = std::function<bool(
57  const std::map<int /* trajectory_id */, mapping::SubmapId>&,
58  const std::map<int /* trajectory_id */, mapping::NodeId>&)>;
59 
60  struct Data {
62  std::unique_ptr<sensor::Data> data;
63  };
65  const int trajectory_id;
66  const int subscription_index;
67  };
68 
69  MapBuilderContextInterface() = default;
70  ~MapBuilderContextInterface() = default;
71 
74  delete;
75 
80  virtual void AddSensorDataToTrajectory(const Data& sensor_data) = 0;
83  virtual void UnsubscribeLocalSlamResults(
84  const LocalSlamSubscriptionId& subscription_id) = 0;
86  GlobalSlamOptimizationCallback callback) = 0;
87  virtual void UnsubscribeGlobalSlamOptimizations(int subscription_index) = 0;
88  virtual void NotifyFinishTrajectory(int trajectory_id) = 0;
90  virtual void EnqueueSensorData(int trajectory_id,
91  std::unique_ptr<sensor::Data> data) = 0;
92  virtual void EnqueueLocalSlamResultData(
93  int trajectory_id, const std::string& sensor_id,
94  const mapping::proto::LocalSlamResultData& local_slam_result_data) = 0;
95 };
96 
97 } // namespace cloud
98 } // namespace cartographer
99 
100 #endif // CARTOGRAPHER_CLOUD_MAP_BUILDER_CONTEXT_INTERFACE_H
virtual void UnsubscribeGlobalSlamOptimizations(int subscription_index)=0
virtual void UnsubscribeLocalSlamResults(const LocalSlamSubscriptionId &subscription_id)=0
std::function< bool(std::unique_ptr< LocalSlamResult >)> LocalSlamSubscriptionCallback
std::function< bool(const std::map< int, mapping::SubmapId > &, const std::map< int, mapping::NodeId > &)> GlobalSlamOptimizationCallback
virtual void EnqueueSensorData(int trajectory_id, std::unique_ptr< sensor::Data > data)=0
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
virtual mapping::MapBuilderInterface & map_builder()=0
virtual LocalSlamSubscriptionId SubscribeLocalSlamResults(int trajectory_id, LocalSlamSubscriptionCallback callback)=0
virtual common::BlockingQueue< std::unique_ptr< Data > > & sensor_data_queue()=0
virtual mapping::TrajectoryBuilderInterface::LocalSlamResultCallback GetLocalSlamResultCallbackForSubscriptions()=0
virtual void AddSensorDataToTrajectory(const Data &sensor_data)=0
virtual int SubscribeGlobalSlamOptimizations(GlobalSlamOptimizationCallback callback)=0
MapBuilderContextInterface & operator=(const MapBuilderContextInterface &)=delete
std::unique_ptr< const mapping::TrajectoryBuilderInterface::InsertionResult > insertion_result
virtual void EnqueueLocalSlamResultData(int trajectory_id, const std::string &sensor_id, const mapping::proto::LocalSlamResultData &local_slam_result_data)=0
virtual LocalTrajectoryUploaderInterface * local_trajectory_uploader()=0
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback
virtual void NotifyFinishTrajectory(int trajectory_id)=0


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