map_builder_server.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_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H
18 #define CARTOGRAPHER_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H
19 
20 #include "async_grpc/execution_context.h"
21 #include "async_grpc/server.h"
25 #include "cartographer/cloud/proto/map_builder_server_options.pb.h"
36 
37 namespace cartographer {
38 namespace cloud {
39 
40 class MapBuilderServer;
41 
42 template <class SubmapType>
44  public:
45  MapBuilderContext(MapBuilderServer* map_builder_server);
48  sensor_data_queue() override;
51  void AddSensorDataToTrajectory(const Data& sensor_data) override;
53  int trajectory_id, LocalSlamSubscriptionCallback callback) override;
55  const LocalSlamSubscriptionId& subscription_id) override;
57  GlobalSlamOptimizationCallback callback) override;
58  void UnsubscribeGlobalSlamOptimizations(int subscription_index) override;
59  void NotifyFinishTrajectory(int trajectory_id) override;
61  void EnqueueSensorData(int trajectory_id,
62  std::unique_ptr<sensor::Data> data) override;
63  void EnqueueLocalSlamResultData(int trajectory_id,
64  const std::string& sensor_id,
65  const mapping::proto::LocalSlamResultData&
66  local_slam_result_data) override;
67 
68  private:
71 };
72 
74  public:
77 
79  const proto::MapBuilderServerOptions& map_builder_server_options,
80  std::unique_ptr<mapping::MapBuilderInterface> map_builder);
82 
83  // Starts the gRPC server, the 'LocalTrajectoryUploader' and the SLAM thread.
84  void Start() final;
85 
86  // Waits for the 'MapBuilderServer' to shut down. Note: The server must be
87  // either shutting down or some other thread must call 'Shutdown()' for this
88  // function to ever return.
89  void WaitForShutdown() final;
90 
91  // Waits until all computation is finished (for testing).
92  void WaitUntilIdle() final;
93 
94  // Shuts down the gRPC server, the 'LocalTrajectoryUploader' and the SLAM
95  // thread.
96  void Shutdown() final;
97 
98  static void RegisterMetrics(metrics::FamilyFactory* family_factory);
99 
100  private:
102  std::map<int /* subscription_index */,
104 
105  void ProcessSensorDataQueue();
106  void StartSlamThread();
107  void OnLocalSlamResult(
108  int trajectory_id, common::Time time, transform::Rigid3d local_pose,
109  sensor::RangeData range_data,
110  std::unique_ptr<
112  insertion_result);
113  void OnGlobalSlamOptimizations(
114  const std::map<int, mapping::SubmapId>& last_optimized_submap_ids,
115  const std::map<int, mapping::NodeId>& last_optimized_node_ids);
117  int trajectory_id,
121  subscription_id);
124  void UnsubscribeGlobalSlamOptimizations(int subscription_index);
125  void NotifyFinishTrajectory(int trajectory_id);
126 
127  bool shutting_down_ = false;
128  std::unique_ptr<std::thread> slam_thread_;
129  std::unique_ptr<async_grpc::Server> grpc_server_;
130  std::unique_ptr<mapping::MapBuilderInterface> map_builder_;
133  common::Mutex subscriptions_lock_;
134  int current_subscription_index_ = 0;
135  std::map<int /* trajectory ID */, LocalSlamResultHandlerSubscriptions>
136  local_slam_subscriptions_ GUARDED_BY(subscriptions_lock_);
137  std::map<int /* subscription_index */,
139  global_slam_subscriptions_ GUARDED_BY(subscriptions_lock_);
140  std::unique_ptr<LocalTrajectoryUploaderInterface> local_trajectory_uploader_;
141  int starting_submap_index_ = 0;
142 };
143 
144 } // namespace cloud
145 } // namespace cartographer
146 
148 
149 #endif // CARTOGRAPHER_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H
mapping::TrajectoryBuilderInterface::LocalSlamResultCallback GetLocalSlamResultCallbackForSubscriptions() override
void AddSensorDataToTrajectory(const Data &sensor_data) override
std::unique_ptr< mapping::MapBuilderInterface > map_builder_
void UnsubscribeGlobalSlamOptimizations(int subscription_index) override
void NotifyFinishTrajectory(int trajectory_id) override
std::function< bool(std::unique_ptr< LocalSlamResult >)> LocalSlamSubscriptionCallback
#define GUARDED_BY(x)
Definition: mutex.h:40
std::function< bool(const std::map< int, mapping::SubmapId > &, const std::map< int, mapping::NodeId > &)> GlobalSlamOptimizationCallback
MapBuilderContextInterface::LocalSlamSubscriptionId SubscribeLocalSlamResults(int trajectory_id, LocalSlamSubscriptionCallback callback) override
std::unique_ptr< async_grpc::Server > grpc_server_
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
static time_point time
bool shutting_down_
std::unique_ptr< LocalTrajectoryUploaderInterface > local_trajectory_uploader_
mapping::MapBuilderInterface & map_builder() override
MapBuilderContext(MapBuilderServer *map_builder_server)
common::BlockingQueue< std::unique_ptr< MapBuilderContextInterface::Data > > & sensor_data_queue() override
std::unique_ptr< std::thread > slam_thread_
LocalTrajectoryUploaderInterface * local_trajectory_uploader() override
void EnqueueSensorData(int trajectory_id, std::unique_ptr< sensor::Data > data) override
void UnsubscribeLocalSlamResults(const LocalSlamSubscriptionId &subscription_id) override
common::BlockingQueue< std::unique_ptr< MapBuilderContextInterface::Data > > incoming_data_queue_
std::map< int, MapBuilderContextInterface::LocalSlamSubscriptionCallback > LocalSlamResultHandlerSubscriptions
int SubscribeGlobalSlamOptimizations(GlobalSlamOptimizationCallback callback) override
mapping::SubmapController< SubmapType > submap_controller_
void EnqueueLocalSlamResultData(int trajectory_id, const std::string &sensor_id, const mapping::proto::LocalSlamResultData &local_slam_result_data) override
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback


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