trajectory_builder_stub.cc
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 #include "cartographer/cloud/internal/client/trajectory_builder_stub.h"
00018 
00019 #include "cartographer/cloud/internal/sensor/serialization.h"
00020 #include "cartographer/cloud/proto/map_builder_service.pb.h"
00021 #include "cartographer/mapping/local_slam_result_data.h"
00022 #include "cartographer/transform/transform.h"
00023 #include "glog/logging.h"
00024 
00025 namespace cartographer {
00026 namespace cloud {
00027 
00028 TrajectoryBuilderStub::TrajectoryBuilderStub(
00029     std::shared_ptr<::grpc::Channel> client_channel, const int trajectory_id,
00030     const std::string& client_id,
00031     LocalSlamResultCallback local_slam_result_callback)
00032     : client_channel_(client_channel),
00033       trajectory_id_(trajectory_id),
00034       client_id_(client_id),
00035       receive_local_slam_results_client_(client_channel_) {
00036   if (local_slam_result_callback) {
00037     proto::ReceiveLocalSlamResultsRequest request;
00038     request.set_trajectory_id(trajectory_id);
00039     receive_local_slam_results_client_.Write(request);
00040     auto* receive_local_slam_results_client_ptr =
00041         &receive_local_slam_results_client_;
00042     receive_local_slam_results_thread_ = absl::make_unique<std::thread>(
00043         [receive_local_slam_results_client_ptr, local_slam_result_callback]() {
00044           RunLocalSlamResultsReader(receive_local_slam_results_client_ptr,
00045                                     local_slam_result_callback);
00046         });
00047   }
00048 }
00049 
00050 TrajectoryBuilderStub::~TrajectoryBuilderStub() {
00051   if (receive_local_slam_results_thread_) {
00052     receive_local_slam_results_thread_->join();
00053   }
00054   if (add_rangefinder_client_) {
00055     CHECK(add_rangefinder_client_->StreamWritesDone());
00056     CHECK(add_rangefinder_client_->StreamFinish().ok());
00057   }
00058   if (add_imu_client_) {
00059     CHECK(add_imu_client_->StreamWritesDone());
00060     CHECK(add_imu_client_->StreamFinish().ok());
00061   }
00062   if (add_odometry_client_) {
00063     CHECK(add_odometry_client_->StreamWritesDone());
00064     CHECK(add_odometry_client_->StreamFinish().ok());
00065   }
00066   if (add_landmark_client_) {
00067     CHECK(add_landmark_client_->StreamWritesDone());
00068     CHECK(add_landmark_client_->StreamFinish().ok());
00069   }
00070   if (add_fixed_frame_pose_client_) {
00071     CHECK(add_fixed_frame_pose_client_->StreamWritesDone());
00072     CHECK(add_fixed_frame_pose_client_->StreamFinish().ok());
00073   }
00074 }
00075 
00076 void TrajectoryBuilderStub::AddSensorData(
00077     const std::string& sensor_id,
00078     const sensor::TimedPointCloudData& timed_point_cloud_data) {
00079   if (!add_rangefinder_client_) {
00080     add_rangefinder_client_ = absl::make_unique<
00081         async_grpc::Client<handlers::AddRangefinderDataSignature>>(
00082         client_channel_);
00083   }
00084   proto::AddRangefinderDataRequest request;
00085   CreateAddRangeFinderDataRequest(sensor_id, trajectory_id_, client_id_,
00086                                   sensor::ToProto(timed_point_cloud_data),
00087                                   &request);
00088   add_rangefinder_client_->Write(request);
00089 }
00090 
00091 void TrajectoryBuilderStub::AddSensorData(const std::string& sensor_id,
00092                                           const sensor::ImuData& imu_data) {
00093   if (!add_imu_client_) {
00094     add_imu_client_ =
00095         absl::make_unique<async_grpc::Client<handlers::AddImuDataSignature>>(
00096             client_channel_);
00097   }
00098   proto::AddImuDataRequest request;
00099   CreateAddImuDataRequest(sensor_id, trajectory_id_, client_id_,
00100                           sensor::ToProto(imu_data), &request);
00101   add_imu_client_->Write(request);
00102 }
00103 
00104 void TrajectoryBuilderStub::AddSensorData(
00105     const std::string& sensor_id, const sensor::OdometryData& odometry_data) {
00106   if (!add_odometry_client_) {
00107     add_odometry_client_ = absl::make_unique<
00108         async_grpc::Client<handlers::AddOdometryDataSignature>>(
00109         client_channel_);
00110   }
00111   proto::AddOdometryDataRequest request;
00112   CreateAddOdometryDataRequest(sensor_id, trajectory_id_, client_id_,
00113                                sensor::ToProto(odometry_data), &request);
00114   add_odometry_client_->Write(request);
00115 }
00116 
00117 void TrajectoryBuilderStub::AddSensorData(
00118     const std::string& sensor_id,
00119     const sensor::FixedFramePoseData& fixed_frame_pose) {
00120   if (!add_fixed_frame_pose_client_) {
00121     add_fixed_frame_pose_client_ = absl::make_unique<
00122         async_grpc::Client<handlers::AddFixedFramePoseDataSignature>>(
00123         client_channel_);
00124   }
00125   proto::AddFixedFramePoseDataRequest request;
00126   CreateAddFixedFramePoseDataRequest(sensor_id, trajectory_id_, client_id_,
00127                                      sensor::ToProto(fixed_frame_pose),
00128                                      &request);
00129   add_fixed_frame_pose_client_->Write(request);
00130 }
00131 
00132 void TrajectoryBuilderStub::AddSensorData(
00133     const std::string& sensor_id, const sensor::LandmarkData& landmark_data) {
00134   if (!add_landmark_client_) {
00135     add_landmark_client_ = absl::make_unique<
00136         async_grpc::Client<handlers::AddLandmarkDataSignature>>(
00137         client_channel_);
00138   }
00139   proto::AddLandmarkDataRequest request;
00140   CreateAddLandmarkDataRequest(sensor_id, trajectory_id_, client_id_,
00141                                sensor::ToProto(landmark_data), &request);
00142   add_landmark_client_->Write(request);
00143 }
00144 
00145 void TrajectoryBuilderStub::AddLocalSlamResultData(
00146     std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) {
00147   LOG(FATAL) << "Not implemented";
00148 }
00149 
00150 void TrajectoryBuilderStub::RunLocalSlamResultsReader(
00151     async_grpc::Client<handlers::ReceiveLocalSlamResultsSignature>* client,
00152     LocalSlamResultCallback local_slam_result_callback) {
00153   proto::ReceiveLocalSlamResultsResponse response;
00154   while (client->StreamRead(&response)) {
00155     int trajectory_id = response.trajectory_id();
00156     common::Time time = common::FromUniversal(response.timestamp());
00157     transform::Rigid3d local_pose = transform::ToRigid3(response.local_pose());
00158     sensor::RangeData range_data = sensor::FromProto(response.range_data());
00159     auto insertion_result =
00160         response.has_insertion_result()
00161             ? absl::make_unique<InsertionResult>(
00162                   InsertionResult{mapping::NodeId{
00163                       response.insertion_result().node_id().trajectory_id(),
00164                       response.insertion_result().node_id().node_index()}})
00165             : nullptr;
00166     local_slam_result_callback(trajectory_id, time, local_pose, range_data,
00167                                std::move(insertion_result));
00168   }
00169   client->StreamFinish();
00170 }
00171 
00172 }  // namespace cloud
00173 }  // namespace cartographer


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