trajectory_builder_stub.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_CLIENT_TRAJECTORY_BUILDER_STUB_H_
00018 #define CARTOGRAPHER_CLOUD_INTERNAL_CLIENT_TRAJECTORY_BUILDER_STUB_H_
00019 
00020 #include <thread>
00021 
00022 #include "async_grpc/client.h"
00023 #include "cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.h"
00024 #include "cartographer/cloud/internal/handlers/add_imu_data_handler.h"
00025 #include "cartographer/cloud/internal/handlers/add_landmark_data_handler.h"
00026 #include "cartographer/cloud/internal/handlers/add_odometry_data_handler.h"
00027 #include "cartographer/cloud/internal/handlers/add_rangefinder_data_handler.h"
00028 #include "cartographer/cloud/internal/handlers/receive_local_slam_results_handler.h"
00029 #include "cartographer/mapping/local_slam_result_data.h"
00030 #include "cartographer/mapping/trajectory_builder_interface.h"
00031 #include "grpc++/grpc++.h"
00032 #include "pose_graph_stub.h"
00033 #include "trajectory_builder_stub.h"
00034 
00035 namespace cartographer {
00036 namespace cloud {
00037 
00038 class TrajectoryBuilderStub : public mapping::TrajectoryBuilderInterface {
00039  public:
00040   TrajectoryBuilderStub(std::shared_ptr<::grpc::Channel> client_channel,
00041                         const int trajectory_id, const std::string& client_id,
00042                         LocalSlamResultCallback local_slam_result_callback);
00043   ~TrajectoryBuilderStub() override;
00044   TrajectoryBuilderStub(const TrajectoryBuilderStub&) = delete;
00045   TrajectoryBuilderStub& operator=(const TrajectoryBuilderStub&) = delete;
00046 
00047   void AddSensorData(
00048       const std::string& sensor_id,
00049       const sensor::TimedPointCloudData& timed_point_cloud_data) override;
00050   void AddSensorData(const std::string& sensor_id,
00051                      const sensor::ImuData& imu_data) override;
00052   void AddSensorData(const std::string& sensor_id,
00053                      const sensor::OdometryData& odometry_data) override;
00054   void AddSensorData(
00055       const std::string& sensor_id,
00056       const sensor::FixedFramePoseData& fixed_frame_pose) override;
00057   void AddSensorData(const std::string& sensor_id,
00058                      const sensor::LandmarkData& landmark_data) override;
00059   void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
00060                                   local_slam_result_data) override;
00061 
00062  private:
00063   static void RunLocalSlamResultsReader(
00064       async_grpc::Client<handlers::ReceiveLocalSlamResultsSignature>*
00065           client_reader,
00066       LocalSlamResultCallback local_slam_result_callback);
00067 
00068   std::shared_ptr<::grpc::Channel> client_channel_;
00069   const int trajectory_id_;
00070   const std::string client_id_;
00071   std::unique_ptr<async_grpc::Client<handlers::AddRangefinderDataSignature>>
00072       add_rangefinder_client_;
00073   std::unique_ptr<async_grpc::Client<handlers::AddImuDataSignature>>
00074       add_imu_client_;
00075   std::unique_ptr<async_grpc::Client<handlers::AddOdometryDataSignature>>
00076       add_odometry_client_;
00077   std::unique_ptr<async_grpc::Client<handlers::AddFixedFramePoseDataSignature>>
00078       add_fixed_frame_pose_client_;
00079   std::unique_ptr<async_grpc::Client<handlers::AddLandmarkDataSignature>>
00080       add_landmark_client_;
00081   async_grpc::Client<handlers::ReceiveLocalSlamResultsSignature>
00082       receive_local_slam_results_client_;
00083   std::unique_ptr<std::thread> receive_local_slam_results_thread_;
00084 };
00085 
00086 }  // namespace cloud
00087 }  // namespace cartographer
00088 
00089 #endif  // CARTOGRAPHER_CLOUD_INTERNAL_CLIENT_TRAJECTORY_BUILDER_STUB_H_


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