map_builder_context_impl.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 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_INTERNAL_CLOUD_MAP_BUILDER_CONTEXT_IMPL_H
00018 #define CARTOGRAPHER_INTERNAL_CLOUD_MAP_BUILDER_CONTEXT_IMPL_H
00019 
00020 namespace cartographer {
00021 namespace cloud {
00022 
00023 template <class SubmapType>
00024 MapBuilderContext<SubmapType>::MapBuilderContext(
00025     MapBuilderServer* map_builder_server)
00026     : map_builder_server_(map_builder_server) {}
00027 
00028 template <class SubmapType>
00029 mapping::MapBuilderInterface& MapBuilderContext<SubmapType>::map_builder() {
00030   return *map_builder_server_->map_builder_;
00031 }
00032 
00033 template <class SubmapType>
00034 common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>&
00035 MapBuilderContext<SubmapType>::sensor_data_queue() {
00036   return map_builder_server_->incoming_data_queue_;
00037 }
00038 
00039 template <class SubmapType>
00040 mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
00041 MapBuilderContext<SubmapType>::GetLocalSlamResultCallbackForSubscriptions() {
00042   return [this](int trajectory_id, common::Time time,
00043                 transform::Rigid3d local_pose, sensor::RangeData range_data,
00044                 std::unique_ptr<
00045                     const mapping::TrajectoryBuilderInterface::InsertionResult>
00046                     insertion_result) {
00047     auto it = client_ids_.find(trajectory_id);
00048     if (it == client_ids_.end()) {
00049       LOG(ERROR) << "Unknown trajectory_id " << trajectory_id << ". Ignoring.";
00050       return;
00051     }
00052     map_builder_server_->OnLocalSlamResult(trajectory_id, it->second, time,
00053                                            local_pose, std::move(range_data),
00054                                            std::move(insertion_result));
00055   };
00056 }
00057 
00058 template <class SubmapType>
00059 void MapBuilderContext<SubmapType>::AddSensorDataToTrajectory(
00060     const Data& sensor_data) {
00061   sensor_data.data->AddToTrajectoryBuilder(
00062       map_builder_server_->map_builder_->GetTrajectoryBuilder(
00063           sensor_data.trajectory_id));
00064 }
00065 
00066 template <class SubmapType>
00067 MapBuilderContextInterface::LocalSlamSubscriptionId
00068 MapBuilderContext<SubmapType>::SubscribeLocalSlamResults(
00069     int trajectory_id, LocalSlamSubscriptionCallback callback) {
00070   return map_builder_server_->SubscribeLocalSlamResults(trajectory_id,
00071                                                         callback);
00072 }
00073 
00074 template <class SubmapType>
00075 void MapBuilderContext<SubmapType>::UnsubscribeLocalSlamResults(
00076     const LocalSlamSubscriptionId& subscription_id) {
00077   map_builder_server_->UnsubscribeLocalSlamResults(subscription_id);
00078 }
00079 
00080 template <class SubmapType>
00081 int MapBuilderContext<SubmapType>::SubscribeGlobalSlamOptimizations(
00082     GlobalSlamOptimizationCallback callback) {
00083   return map_builder_server_->SubscribeGlobalSlamOptimizations(callback);
00084 }
00085 
00086 template <class SubmapType>
00087 void MapBuilderContext<SubmapType>::UnsubscribeGlobalSlamOptimizations(
00088     int subscription_index) {
00089   map_builder_server_->UnsubscribeGlobalSlamOptimizations(subscription_index);
00090 }
00091 
00092 template <class SubmapType>
00093 void MapBuilderContext<SubmapType>::NotifyFinishTrajectory(int trajectory_id) {
00094   map_builder_server_->NotifyFinishTrajectory(trajectory_id);
00095 }
00096 
00097 template <class SubmapType>
00098 LocalTrajectoryUploaderInterface*
00099 MapBuilderContext<SubmapType>::local_trajectory_uploader() {
00100   return map_builder_server_->local_trajectory_uploader_.get();
00101 }
00102 
00103 template <class SubmapType>
00104 void MapBuilderContext<SubmapType>::EnqueueSensorData(
00105     int trajectory_id, std::unique_ptr<sensor::Data> data) {
00106   map_builder_server_->incoming_data_queue_.Push(
00107       absl::make_unique<Data>(Data{trajectory_id, std::move(data)}));
00108 }
00109 
00110 template <class SubmapType>
00111 void MapBuilderContext<SubmapType>::RegisterClientIdForTrajectory(
00112     const std::string& client_id, int trajectory_id) {
00113   CHECK_EQ(client_ids_.count(trajectory_id), 0u);
00114   LOG(INFO) << "Registering trajectory_id " << trajectory_id << " to client_id "
00115             << client_id;
00116   client_ids_[trajectory_id] = client_id;
00117 }
00118 
00119 template <class SubmapType>
00120 bool MapBuilderContext<SubmapType>::CheckClientIdForTrajectory(
00121     const std::string& client_id, int trajectory_id) {
00122   return (client_ids_.count(trajectory_id) > 0 &&
00123           client_ids_[trajectory_id] == client_id);
00124 }
00125 
00126 template <>
00127 void MapBuilderContext<mapping::Submap2D>::EnqueueLocalSlamResultData(
00128     int trajectory_id, const std::string& sensor_id,
00129     const mapping::proto::LocalSlamResultData& local_slam_result_data);
00130 template <>
00131 void MapBuilderContext<mapping::Submap3D>::EnqueueLocalSlamResultData(
00132     int trajectory_id, const std::string& sensor_id,
00133     const mapping::proto::LocalSlamResultData& local_slam_result_data);
00134 
00135 }  // namespace cloud
00136 }  // namespace cartographer
00137 
00138 #endif  // CARTOGRAPHER_INTERNAL_CLOUD_MAP_BUILDER_CONTEXT_IMPL_H


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