map_builder_server.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 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_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H
00018 #define CARTOGRAPHER_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H
00019 
00020 #include "async_grpc/execution_context.h"
00021 #include "async_grpc/server.h"
00022 #include "cartographer/cloud/internal/local_trajectory_uploader.h"
00023 #include "cartographer/cloud/internal/map_builder_context_interface.h"
00024 #include "cartographer/cloud/map_builder_server_interface.h"
00025 #include "cartographer/cloud/proto/map_builder_server_options.pb.h"
00026 #include "cartographer/common/blocking_queue.h"
00027 #include "cartographer/common/time.h"
00028 #include "cartographer/mapping/2d/submap_2d.h"
00029 #include "cartographer/mapping/3d/submap_3d.h"
00030 #include "cartographer/mapping/internal/submap_controller.h"
00031 #include "cartographer/mapping/local_slam_result_data.h"
00032 #include "cartographer/mapping/map_builder.h"
00033 #include "cartographer/mapping/trajectory_builder_interface.h"
00034 #include "cartographer/metrics/family_factory.h"
00035 #include "cartographer/sensor/internal/dispatchable.h"
00036 
00037 namespace cartographer {
00038 namespace cloud {
00039 
00040 class MapBuilderServer;
00041 
00042 template <class SubmapType>
00043 class MapBuilderContext : public MapBuilderContextInterface {
00044  public:
00045   MapBuilderContext(MapBuilderServer* map_builder_server);
00046   mapping::MapBuilderInterface& map_builder() override;
00047   common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>&
00048   sensor_data_queue() override;
00049   mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
00050   GetLocalSlamResultCallbackForSubscriptions() override;
00051   void AddSensorDataToTrajectory(const Data& sensor_data) override;
00052   MapBuilderContextInterface::LocalSlamSubscriptionId SubscribeLocalSlamResults(
00053       int trajectory_id, LocalSlamSubscriptionCallback callback) override;
00054   void UnsubscribeLocalSlamResults(
00055       const LocalSlamSubscriptionId& subscription_id) override;
00056   int SubscribeGlobalSlamOptimizations(
00057       GlobalSlamOptimizationCallback callback) override;
00058   void UnsubscribeGlobalSlamOptimizations(int subscription_index) override;
00059   void NotifyFinishTrajectory(int trajectory_id) override;
00060   LocalTrajectoryUploaderInterface* local_trajectory_uploader() override;
00061   void EnqueueSensorData(int trajectory_id,
00062                          std::unique_ptr<sensor::Data> data) override;
00063   void EnqueueLocalSlamResultData(int trajectory_id,
00064                                   const std::string& sensor_id,
00065                                   const mapping::proto::LocalSlamResultData&
00066                                       local_slam_result_data) override;
00067   void RegisterClientIdForTrajectory(const std::string& client_id,
00068                                      int trajectory_id) override;
00069   bool CheckClientIdForTrajectory(const std::string& client_id,
00070                                   int trajectory_id) override;
00071 
00072  private:
00073   MapBuilderServer* map_builder_server_;
00074   mapping::SubmapController<SubmapType> submap_controller_;
00075   std::map</*trajectory_id=*/int, /*client_id=*/std::string> client_ids_;
00076 };
00077 
00078 class MapBuilderServer : public MapBuilderServerInterface {
00079  public:
00080   friend MapBuilderContext<mapping::Submap2D>;
00081   friend MapBuilderContext<mapping::Submap3D>;
00082 
00083   MapBuilderServer(
00084       const proto::MapBuilderServerOptions& map_builder_server_options,
00085       std::unique_ptr<mapping::MapBuilderInterface> map_builder);
00086   ~MapBuilderServer() {}
00087 
00088   // Starts the gRPC server, the 'LocalTrajectoryUploader' and the SLAM thread.
00089   void Start() final;
00090 
00091   // Waits for the 'MapBuilderServer' to shut down. Note: The server must be
00092   // either shutting down or some other thread must call 'Shutdown()' for this
00093   // function to ever return.
00094   void WaitForShutdown() final;
00095 
00096   // Waits until all computation is finished (for testing).
00097   void WaitUntilIdle() final;
00098 
00099   // Shuts down the gRPC server, the 'LocalTrajectoryUploader' and the SLAM
00100   // thread.
00101   void Shutdown() final;
00102 
00103   static void RegisterMetrics(metrics::FamilyFactory* family_factory);
00104 
00105  private:
00106   using LocalSlamResultHandlerSubscriptions =
00107       std::map<int /* subscription_index */,
00108                MapBuilderContextInterface::LocalSlamSubscriptionCallback>;
00109 
00110   void ProcessSensorDataQueue();
00111   void StartSlamThread();
00112   void OnLocalSlamResult(
00113       int trajectory_id, const std::string client_id, common::Time time,
00114       transform::Rigid3d local_pose, sensor::RangeData range_data,
00115       std::unique_ptr<
00116           const mapping::TrajectoryBuilderInterface::InsertionResult>
00117           insertion_result);
00118   void OnGlobalSlamOptimizations(
00119       const std::map<int, mapping::SubmapId>& last_optimized_submap_ids,
00120       const std::map<int, mapping::NodeId>& last_optimized_node_ids);
00121   MapBuilderContextInterface::LocalSlamSubscriptionId SubscribeLocalSlamResults(
00122       int trajectory_id,
00123       MapBuilderContextInterface::LocalSlamSubscriptionCallback callback);
00124   void UnsubscribeLocalSlamResults(
00125       const MapBuilderContextInterface::LocalSlamSubscriptionId&
00126           subscription_id);
00127   int SubscribeGlobalSlamOptimizations(
00128       MapBuilderContextInterface::GlobalSlamOptimizationCallback callback);
00129   void UnsubscribeGlobalSlamOptimizations(int subscription_index);
00130   void NotifyFinishTrajectory(int trajectory_id);
00131 
00132   bool shutting_down_ = false;
00133   std::unique_ptr<std::thread> slam_thread_;
00134   std::unique_ptr<async_grpc::Server> grpc_server_;
00135   std::unique_ptr<mapping::MapBuilderInterface> map_builder_;
00136   common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>
00137       incoming_data_queue_;
00138   absl::Mutex subscriptions_lock_;
00139   int current_subscription_index_ = 0;
00140   std::map<int /* trajectory ID */, LocalSlamResultHandlerSubscriptions>
00141       local_slam_subscriptions_ GUARDED_BY(subscriptions_lock_);
00142   std::map<int /* subscription_index */,
00143            MapBuilderContextInterface::GlobalSlamOptimizationCallback>
00144       global_slam_subscriptions_ GUARDED_BY(subscriptions_lock_);
00145   std::unique_ptr<LocalTrajectoryUploaderInterface> local_trajectory_uploader_;
00146   int starting_submap_index_ = 0;
00147 };
00148 
00149 }  // namespace cloud
00150 }  // namespace cartographer
00151 
00152 #include "cartographer/cloud/internal/map_builder_context_impl.h"
00153 
00154 #endif  // CARTOGRAPHER_CLOUD_INTERNAL_MAP_BUILDER_SERVER_H


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