map_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/client/map_builder_stub.h"
00018 
00019 #include "cartographer/cloud/internal/client/pose_graph_stub.h"
00020 #include "cartographer/cloud/internal/client/trajectory_builder_stub.h"
00021 #include "cartographer/cloud/internal/handlers/add_trajectory_handler.h"
00022 #include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h"
00023 #include "cartographer/cloud/internal/handlers/get_submap_handler.h"
00024 #include "cartographer/cloud/internal/handlers/load_state_from_file_handler.h"
00025 #include "cartographer/cloud/internal/handlers/load_state_handler.h"
00026 #include "cartographer/cloud/internal/handlers/write_state_handler.h"
00027 #include "cartographer/cloud/internal/handlers/write_state_to_file_handler.h"
00028 #include "cartographer/cloud/internal/mapping/serialization.h"
00029 #include "cartographer/cloud/internal/sensor/serialization.h"
00030 #include "cartographer/cloud/proto/map_builder_service.pb.h"
00031 #include "cartographer/io/proto_stream_deserializer.h"
00032 #include "glog/logging.h"
00033 
00034 namespace cartographer {
00035 namespace cloud {
00036 namespace {
00037 
00038 using absl::make_unique;
00039 constexpr int kChannelTimeoutSeconds = 10;
00040 constexpr int kRetryBaseDelayMilliseconds = 500;
00041 constexpr float kRetryDelayFactor = 2.0;
00042 constexpr int kMaxRetries = 5;
00043 
00044 }  // namespace
00045 
00046 MapBuilderStub::MapBuilderStub(const std::string& server_address,
00047                                const std::string& client_id)
00048     : client_channel_(::grpc::CreateChannel(
00049           server_address, ::grpc::InsecureChannelCredentials())),
00050       pose_graph_stub_(make_unique<PoseGraphStub>(client_channel_, client_id)),
00051       client_id_(client_id) {
00052   LOG(INFO) << "Connecting to SLAM process at " << server_address
00053             << " with client_id " << client_id;
00054   std::chrono::system_clock::time_point deadline(
00055       std::chrono::system_clock::now() +
00056       std::chrono::seconds(kChannelTimeoutSeconds));
00057   if (!client_channel_->WaitForConnected(deadline)) {
00058     LOG(FATAL) << "Failed to connect to " << server_address;
00059   }
00060 }
00061 
00062 int MapBuilderStub::AddTrajectoryBuilder(
00063     const std::set<SensorId>& expected_sensor_ids,
00064     const mapping::proto::TrajectoryBuilderOptions& trajectory_options,
00065     LocalSlamResultCallback local_slam_result_callback) {
00066   proto::AddTrajectoryRequest request;
00067   request.set_client_id(client_id_);
00068   *request.mutable_trajectory_builder_options() = trajectory_options;
00069   for (const auto& sensor_id : expected_sensor_ids) {
00070     *request.add_expected_sensor_ids() = cloud::ToProto(sensor_id);
00071   }
00072   async_grpc::Client<handlers::AddTrajectorySignature> client(
00073       client_channel_, common::FromSeconds(kChannelTimeoutSeconds),
00074       async_grpc::CreateLimitedBackoffStrategy(
00075           common::FromMilliseconds(kRetryBaseDelayMilliseconds),
00076           kRetryDelayFactor, kMaxRetries));
00077   CHECK(client.Write(request));
00078 
00079   // Construct trajectory builder stub.
00080   trajectory_builder_stubs_.emplace(
00081       std::piecewise_construct,
00082       std::forward_as_tuple(client.response().trajectory_id()),
00083       std::forward_as_tuple(make_unique<TrajectoryBuilderStub>(
00084           client_channel_, client.response().trajectory_id(), client_id_,
00085           local_slam_result_callback)));
00086   return client.response().trajectory_id();
00087 }
00088 
00089 int MapBuilderStub::AddTrajectoryForDeserialization(
00090     const mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
00091         options_with_sensor_ids_proto) {
00092   LOG(FATAL) << "Not implemented";
00093 }
00094 
00095 mapping::TrajectoryBuilderInterface* MapBuilderStub::GetTrajectoryBuilder(
00096     int trajectory_id) const {
00097   auto it = trajectory_builder_stubs_.find(trajectory_id);
00098   if (it == trajectory_builder_stubs_.end()) {
00099     return nullptr;
00100   }
00101   return it->second.get();
00102 }
00103 
00104 void MapBuilderStub::FinishTrajectory(int trajectory_id) {
00105   proto::FinishTrajectoryRequest request;
00106   request.set_client_id(client_id_);
00107   request.set_trajectory_id(trajectory_id);
00108   async_grpc::Client<handlers::FinishTrajectorySignature> client(
00109       client_channel_);
00110   ::grpc::Status status;
00111   client.Write(request, &status);
00112   if (!status.ok()) {
00113     LOG(ERROR) << "Failed to finish trajectory " << trajectory_id
00114                << " for client_id " << client_id_ << ": "
00115                << status.error_message();
00116     return;
00117   }
00118   trajectory_builder_stubs_.erase(trajectory_id);
00119 }
00120 
00121 std::string MapBuilderStub::SubmapToProto(
00122     const mapping::SubmapId& submap_id,
00123     mapping::proto::SubmapQuery::Response* submap_query_response) {
00124   proto::GetSubmapRequest request;
00125   submap_id.ToProto(request.mutable_submap_id());
00126   async_grpc::Client<handlers::GetSubmapSignature> client(client_channel_);
00127   CHECK(client.Write(request));
00128   submap_query_response->CopyFrom(client.response().submap_query_response());
00129   return client.response().error_msg();
00130 }
00131 
00132 void MapBuilderStub::SerializeState(bool include_unfinished_submaps,
00133                                     io::ProtoStreamWriterInterface* writer) {
00134   if (include_unfinished_submaps) {
00135     LOG(WARNING) << "Serializing unfinished submaps is currently unsupported. "
00136                     "Proceeding to write the state without them.";
00137   }
00138   google::protobuf::Empty request;
00139   async_grpc::Client<handlers::WriteStateSignature> client(client_channel_);
00140   CHECK(client.Write(request));
00141   proto::WriteStateResponse response;
00142   while (client.StreamRead(&response)) {
00143     switch (response.state_chunk_case()) {
00144       case proto::WriteStateResponse::kHeader:
00145         writer->WriteProto(response.header());
00146         break;
00147       case proto::WriteStateResponse::kSerializedData:
00148         writer->WriteProto(response.serialized_data());
00149         break;
00150       default:
00151         LOG(FATAL) << "Unhandled message type";
00152     }
00153   }
00154 }
00155 
00156 bool MapBuilderStub::SerializeStateToFile(bool include_unfinished_submaps,
00157                                           const std::string& filename) {
00158   if (include_unfinished_submaps) {
00159     LOG(WARNING) << "Serializing unfinished submaps is currently unsupported. "
00160                     "Proceeding to write the state without them.";
00161   }
00162   proto::WriteStateToFileRequest request;
00163   request.set_filename(filename);
00164   ::grpc::Status status;
00165   async_grpc::Client<handlers::WriteStateToFileSignature> client(
00166       client_channel_);
00167   if (!client.Write(request, &status)) {
00168     LOG(ERROR) << "WriteStateToFileRequest failed - "
00169                << "code: " << status.error_code()
00170                << " reason: " << status.error_message();
00171   }
00172   return client.response().success();
00173 }
00174 
00175 std::map<int, int> MapBuilderStub::LoadState(
00176     io::ProtoStreamReaderInterface* reader, const bool load_frozen_state) {
00177   async_grpc::Client<handlers::LoadStateSignature> client(client_channel_);
00178   {
00179     proto::LoadStateRequest request;
00180     request.set_client_id(client_id_);
00181     CHECK(client.Write(request));
00182   }
00183 
00184   io::ProtoStreamDeserializer deserializer(reader);
00185   // Request with the SerializationHeader proto is sent first.
00186   {
00187     proto::LoadStateRequest request;
00188     *request.mutable_serialization_header() = deserializer.header();
00189     request.set_load_frozen_state(load_frozen_state);
00190     CHECK(client.Write(request));
00191   }
00192   // Request with a PoseGraph proto is sent second.
00193   {
00194     proto::LoadStateRequest request;
00195     *request.mutable_serialized_data()->mutable_pose_graph() =
00196         deserializer.pose_graph();
00197     request.set_load_frozen_state(load_frozen_state);
00198     CHECK(client.Write(request));
00199   }
00200   // Request with an AllTrajectoryBuilderOptions should be third.
00201   {
00202     proto::LoadStateRequest request;
00203     *request.mutable_serialized_data()
00204          ->mutable_all_trajectory_builder_options() =
00205         deserializer.all_trajectory_builder_options();
00206     request.set_load_frozen_state(load_frozen_state);
00207     CHECK(client.Write(request));
00208   }
00209   // Multiple requests with SerializedData are sent after.
00210   proto::LoadStateRequest request;
00211   while (
00212       deserializer.ReadNextSerializedData(request.mutable_serialized_data())) {
00213     request.set_load_frozen_state(load_frozen_state);
00214     CHECK(client.Write(request));
00215   }
00216 
00217   CHECK(reader->eof());
00218   CHECK(client.StreamWritesDone());
00219   CHECK(client.StreamFinish().ok());
00220   return FromProto(client.response().trajectory_remapping());
00221 }
00222 
00223 std::map<int, int> MapBuilderStub::LoadStateFromFile(
00224     const std::string& filename, const bool load_frozen_state) {
00225   proto::LoadStateFromFileRequest request;
00226   request.set_file_path(filename);
00227   request.set_client_id(client_id_);
00228   request.set_load_frozen_state(load_frozen_state);
00229   async_grpc::Client<handlers::LoadStateFromFileSignature> client(
00230       client_channel_);
00231   CHECK(client.Write(request));
00232   return FromProto(client.response().trajectory_remapping());
00233 }
00234 
00235 int MapBuilderStub::num_trajectory_builders() const {
00236   return trajectory_builder_stubs_.size();
00237 }
00238 
00239 mapping::PoseGraphInterface* MapBuilderStub::pose_graph() {
00240   return pose_graph_stub_.get();
00241 }
00242 
00243 const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
00244 MapBuilderStub::GetAllTrajectoryBuilderOptions() const {
00245   LOG(FATAL) << "Not implemented";
00246 }
00247 
00248 }  // namespace cloud
00249 }  // namespace cartographer


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