pose_graph_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 #include "async_grpc/client.h"
30 #include "glog/logging.h"
31 
32 namespace cartographer {
33 namespace cloud {
34 
35 PoseGraphStub::PoseGraphStub(std::shared_ptr<::grpc::Channel> client_channel)
36  : client_channel_(client_channel) {}
37 
39  google::protobuf::Empty request;
40  async_grpc::Client<handlers::RunFinalOptimizationSignature> client(
42  CHECK(client.Write(request));
43 }
44 
47  LOG(FATAL) << "Not implemented";
48 }
49 
52  google::protobuf::Empty request;
53  async_grpc::Client<handlers::GetAllSubmapPosesSignature> client(
55  CHECK(client.Write(request));
57  submap_poses;
58  for (const auto& submap_pose : client.response().submap_poses()) {
59  submap_poses.Insert(
60  mapping::SubmapId{submap_pose.submap_id().trajectory_id(),
61  submap_pose.submap_id().submap_index()},
63  submap_pose.submap_version(),
64  transform::ToRigid3(submap_pose.global_pose())});
65  }
66  return submap_poses;
67 }
68 
70  int trajectory_id) const {
71  proto::GetLocalToGlobalTransformRequest request;
72  request.set_trajectory_id(trajectory_id);
73  async_grpc::Client<handlers::GetLocalToGlobalTransformSignature> client(
75  CHECK(client.Write(request));
76  return transform::ToRigid3(client.response().local_to_global());
77 }
78 
81  LOG(FATAL) << "Not implemented";
82 }
83 
86  google::protobuf::Empty request;
87  async_grpc::Client<handlers::GetTrajectoryNodePosesSignature> client(
89  CHECK(client.Write(request));
91  for (const auto& node_pose : client.response().node_poses()) {
93  constant_pose_data;
94  if (node_pose.has_constant_pose_data()) {
96  common::FromUniversal(node_pose.constant_pose_data().timestamp()),
97  transform::ToRigid3(node_pose.constant_pose_data().local_pose())};
98  }
99  node_poses.Insert(
100  mapping::NodeId{node_pose.node_id().trajectory_id(),
101  node_pose.node_id().node_index()},
103  transform::ToRigid3(node_pose.global_pose()), constant_pose_data});
104  }
105  return node_poses;
106 }
107 
108 std::map<std::string, transform::Rigid3d> PoseGraphStub::GetLandmarkPoses()
109  const {
110  google::protobuf::Empty request;
111  async_grpc::Client<handlers::GetLandmarkPosesSignature> client(
113  CHECK(client.Write(request));
114  std::map<std::string, transform::Rigid3d> landmark_poses;
115  for (const auto& landmark_pose : client.response().landmark_poses()) {
116  landmark_poses[landmark_pose.landmark_id()] =
117  transform::ToRigid3(landmark_pose.global_pose());
118  }
119  return landmark_poses;
120 }
121 
122 void PoseGraphStub::SetLandmarkPose(const std::string& landmark_id,
123  const transform::Rigid3d& global_pose) {
124  proto::SetLandmarkPoseRequest request;
125  request.mutable_landmark_pose()->set_landmark_id(landmark_id);
126  *request.mutable_landmark_pose()->mutable_global_pose() =
127  transform::ToProto(global_pose);
128  async_grpc::Client<handlers::SetLandmarkPoseSignature> client(
130  CHECK(client.Write(request));
131 }
132 
133 bool PoseGraphStub::IsTrajectoryFinished(int trajectory_id) const {
134  proto::IsTrajectoryFinishedRequest request;
135  request.set_trajectory_id(trajectory_id);
136  async_grpc::Client<handlers::IsTrajectoryFinishedSignature> client(
138  CHECK(client.Write(request));
139  return client.response().is_finished();
140 }
141 
142 bool PoseGraphStub::IsTrajectoryFrozen(int trajectory_id) const {
143  proto::IsTrajectoryFrozenRequest request;
144  request.set_trajectory_id(trajectory_id);
145  async_grpc::Client<handlers::IsTrajectoryFrozenSignature> client(
147  CHECK(client.Write(request));
148  return client.response().is_frozen();
149 }
150 
151 std::map<int, mapping::PoseGraphInterface::TrajectoryData>
153  LOG(FATAL) << "Not implemented";
154 }
155 
156 std::vector<mapping::PoseGraphInterface::Constraint>
158  google::protobuf::Empty request;
159  async_grpc::Client<handlers::GetConstraintsSignature> client(client_channel_);
160  CHECK(client.Write(request));
161  return mapping::FromProto(client.response().constraints());
162 }
163 
164 mapping::proto::PoseGraph PoseGraphStub::ToProto() const {
165  LOG(FATAL) << "Not implemented";
166 }
167 
170  LOG(FATAL) << "Not implemented";
171 }
172 
173 } // namespace cloud
174 } // namespace cartographer
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
Definition: pose_graph.cc:38
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const override
bool IsTrajectoryFrozen(int trajectory_id) const override
std::vector< Constraint > constraints() const override
void SetGlobalSlamOptimizationCallback(GlobalSlamOptimizationCallback callback) override
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
void Insert(const IdType &id, const DataType &data)
Definition: id.h:280
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const override
std::map< int, mapping::PoseGraphInterface::TrajectoryData > GetTrajectoryData() const override
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
bool IsTrajectoryFinished(int trajectory_id) const override
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
Definition: transform.cc:48
mapping::MapById< mapping::NodeId, mapping::TrajectoryNodePose > GetTrajectoryNodePoses() const override
mapping::MapById< mapping::SubmapId, SubmapData > GetAllSubmapData() const override
PoseGraphStub(std::shared_ptr<::grpc::Channel > client_channel)
void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose) override
mapping::MapById< mapping::SubmapId, SubmapPose > GetAllSubmapPoses() const override
std::shared_ptr<::grpc::Channel > client_channel_
mapping::MapById< mapping::NodeId, mapping::TrajectoryNode > GetTrajectoryNodes() const override
mapping::proto::PoseGraph ToProto() const override
std::shared_ptr<::grpc::Channel > client_channel_


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