trajectory_builder_stub.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2017 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
20 #include "cartographer/cloud/proto/map_builder_service.pb.h"
23 #include "glog/logging.h"
24 
25 namespace cartographer {
26 namespace cloud {
27 
29  std::shared_ptr<::grpc::Channel> client_channel, const int trajectory_id,
30  LocalSlamResultCallback local_slam_result_callback)
31  : client_channel_(client_channel),
32  trajectory_id_(trajectory_id),
33  receive_local_slam_results_client_(client_channel_) {
34  if (local_slam_result_callback) {
35  proto::ReceiveLocalSlamResultsRequest request;
36  request.set_trajectory_id(trajectory_id);
38  auto* receive_local_slam_results_client_ptr =
40  receive_local_slam_results_thread_ = common::make_unique<std::thread>(
41  [receive_local_slam_results_client_ptr, local_slam_result_callback]() {
42  RunLocalSlamResultsReader(receive_local_slam_results_client_ptr,
43  local_slam_result_callback);
44  });
45  }
46 }
47 
51  }
53  CHECK(add_rangefinder_client_->StreamWritesDone());
54  CHECK(add_rangefinder_client_->StreamFinish().ok());
55  }
56  if (add_imu_client_) {
57  CHECK(add_imu_client_->StreamWritesDone());
58  CHECK(add_imu_client_->StreamFinish().ok());
59  }
61  CHECK(add_odometry_client_->StreamWritesDone());
62  CHECK(add_odometry_client_->StreamFinish().ok());
63  }
65  CHECK(add_landmark_client_->StreamWritesDone());
66  CHECK(add_landmark_client_->StreamFinish().ok());
67  }
69  CHECK(add_fixed_frame_pose_client_->StreamWritesDone());
70  CHECK(add_fixed_frame_pose_client_->StreamFinish().ok());
71  }
72 }
73 
75  const std::string& sensor_id,
76  const sensor::TimedPointCloudData& timed_point_cloud_data) {
79  async_grpc::Client<handlers::AddRangefinderDataSignature>>(
81  }
82  proto::AddRangefinderDataRequest request;
84  sensor::ToProto(timed_point_cloud_data),
85  &request);
86  add_rangefinder_client_->Write(request);
87 }
88 
89 void TrajectoryBuilderStub::AddSensorData(const std::string& sensor_id,
90  const sensor::ImuData& imu_data) {
91  if (!add_imu_client_) {
93  common::make_unique<async_grpc::Client<handlers::AddImuDataSignature>>(
95  }
96  proto::AddImuDataRequest request;
98  &request);
99  add_imu_client_->Write(request);
100 }
101 
103  const std::string& sensor_id, const sensor::OdometryData& odometry_data) {
104  if (!add_odometry_client_) {
106  async_grpc::Client<handlers::AddOdometryDataSignature>>(
108  }
109  proto::AddOdometryDataRequest request;
111  sensor::ToProto(odometry_data), &request);
112  add_odometry_client_->Write(request);
113 }
114 
116  const std::string& sensor_id,
117  const sensor::FixedFramePoseData& fixed_frame_pose) {
120  async_grpc::Client<handlers::AddFixedFramePoseDataSignature>>(
122  }
123  proto::AddFixedFramePoseDataRequest request;
125  sensor_id, trajectory_id_, sensor::ToProto(fixed_frame_pose), &request);
126  add_fixed_frame_pose_client_->Write(request);
127 }
128 
130  const std::string& sensor_id, const sensor::LandmarkData& landmark_data) {
131  if (!add_landmark_client_) {
133  async_grpc::Client<handlers::AddLandmarkDataSignature>>(
135  }
136  proto::AddLandmarkDataRequest request;
138  sensor::ToProto(landmark_data), &request);
139  add_landmark_client_->Write(request);
140 }
141 
143  std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) {
144  LOG(FATAL) << "Not implemented";
145 }
146 
148  async_grpc::Client<handlers::ReceiveLocalSlamResultsSignature>* client,
149  LocalSlamResultCallback local_slam_result_callback) {
150  proto::ReceiveLocalSlamResultsResponse response;
151  while (client->StreamRead(&response)) {
152  int trajectory_id = response.trajectory_id();
153  common::Time time = common::FromUniversal(response.timestamp());
154  transform::Rigid3d local_pose = transform::ToRigid3(response.local_pose());
155  sensor::RangeData range_data = sensor::FromProto(response.range_data());
156  auto insertion_result =
157  response.has_insertion_result()
158  ? common::make_unique<InsertionResult>(
160  response.insertion_result().node_id().trajectory_id(),
161  response.insertion_result().node_id().node_index()}})
162  : nullptr;
163  local_slam_result_callback(trajectory_id, time, local_pose, range_data,
164  std::move(insertion_result));
165  }
166  client->StreamFinish();
167 }
168 
169 } // namespace cloud
170 } // namespace cartographer
std::unique_ptr< async_grpc::Client< handlers::AddFixedFramePoseDataSignature > > add_fixed_frame_pose_client_
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
std::unique_ptr< async_grpc::Client< handlers::AddImuDataSignature > > add_imu_client_
void AddSensorData(const std::string &sensor_id, const sensor::TimedPointCloudData &timed_point_cloud_data) override
void CreateAddRangeFinderDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::TimedPointCloudData &timed_point_cloud_data, proto::AddRangefinderDataRequest *proto)
proto::FixedFramePoseData ToProto(const FixedFramePoseData &pose_data)
FixedFramePoseData FromProto(const proto::FixedFramePoseData &proto)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
int trajectory_id_
std::unique_ptr< async_grpc::Client< handlers::AddLandmarkDataSignature > > add_landmark_client_
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
static time_point time
std::shared_ptr<::grpc::Channel > client_channel_
void AddLocalSlamResultData(std::unique_ptr< mapping::LocalSlamResultData > local_slam_result_data) override
static void RunLocalSlamResultsReader(async_grpc::Client< handlers::ReceiveLocalSlamResultsSignature > *client_reader, LocalSlamResultCallback local_slam_result_callback)
async_grpc::Client< handlers::ReceiveLocalSlamResultsSignature > receive_local_slam_results_client_
void CreateAddOdometryDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::OdometryData &odometry_data, proto::AddOdometryDataRequest *proto)
std::unique_ptr< async_grpc::Client< handlers::AddRangefinderDataSignature > > add_rangefinder_client_
std::unique_ptr< async_grpc::Client< handlers::AddOdometryDataSignature > > add_odometry_client_
std::unique_ptr< std::thread > receive_local_slam_results_thread_
void CreateAddFixedFramePoseDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::FixedFramePoseData &fixed_frame_pose_data, proto::AddFixedFramePoseDataRequest *proto)
void CreateAddLandmarkDataRequest(const std::string &sensor_id, int trajectory_id, const sensor::proto::LandmarkData &landmark_data, proto::AddLandmarkDataRequest *proto)
void CreateAddImuDataRequest(const std::string &sensor_id, const int trajectory_id, const sensor::proto::ImuData &imu_data, proto::AddImuDataRequest *proto)
std::shared_ptr<::grpc::Channel > client_channel_
TrajectoryBuilderStub(std::shared_ptr<::grpc::Channel > client_channel, const int trajectory_id, LocalSlamResultCallback local_slam_result_callback)
std::function< void(int, common::Time, transform::Rigid3d, sensor::RangeData, std::unique_ptr< const InsertionResult >)> LocalSlamResultCallback


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58