pose_graph.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 
22 #include "glog/logging.h"
23 
24 namespace cartographer {
25 namespace mapping {
26 
27 proto::PoseGraph::Constraint::Tag ToProto(
28  const PoseGraph::Constraint::Tag& tag) {
29  switch (tag) {
30  case PoseGraph::Constraint::Tag::INTRA_SUBMAP:
31  return proto::PoseGraph::Constraint::INTRA_SUBMAP;
32  case PoseGraph::Constraint::Tag::INTER_SUBMAP:
33  return proto::PoseGraph::Constraint::INTER_SUBMAP;
34  }
35  LOG(FATAL) << "Unsupported tag.";
36 }
37 
39  const proto::PoseGraph::Constraint::Tag& proto) {
40  switch (proto) {
41  case proto::PoseGraph::Constraint::INTRA_SUBMAP:
42  return PoseGraph::Constraint::Tag::INTRA_SUBMAP;
43  case proto::PoseGraph::Constraint::INTER_SUBMAP:
44  return PoseGraph::Constraint::Tag::INTER_SUBMAP;
45  case ::google::protobuf::kint32max:
46  case ::google::protobuf::kint32min: {
47  }
48  }
49  LOG(FATAL) << "Unsupported tag.";
50 }
51 
52 std::vector<PoseGraph::Constraint> FromProto(
53  const ::google::protobuf::RepeatedPtrField<proto::PoseGraph::Constraint>&
54  constraint_protos) {
55  std::vector<PoseGraph::Constraint> constraints;
56  for (const auto& constraint_proto : constraint_protos) {
57  const mapping::SubmapId submap_id{
58  constraint_proto.submap_id().trajectory_id(),
59  constraint_proto.submap_id().submap_index()};
60  const mapping::NodeId node_id{constraint_proto.node_id().trajectory_id(),
61  constraint_proto.node_id().node_index()};
62  const PoseGraph::Constraint::Pose pose{
63  transform::ToRigid3(constraint_proto.relative_pose()),
64  constraint_proto.translation_weight(),
65  constraint_proto.rotation_weight()};
66  const PoseGraph::Constraint::Tag tag = FromProto(constraint_proto.tag());
67  constraints.push_back(PoseGraph::Constraint{submap_id, node_id, pose, tag});
68  }
69  return constraints;
70 }
71 
72 proto::PoseGraphOptions CreatePoseGraphOptions(
73  common::LuaParameterDictionary* const parameter_dictionary) {
74  proto::PoseGraphOptions options;
75  options.set_optimize_every_n_nodes(
76  parameter_dictionary->GetInt("optimize_every_n_nodes"));
77  *options.mutable_constraint_builder_options() =
79  parameter_dictionary->GetDictionary("constraint_builder").get());
80  options.set_matcher_translation_weight(
81  parameter_dictionary->GetDouble("matcher_translation_weight"));
82  options.set_matcher_rotation_weight(
83  parameter_dictionary->GetDouble("matcher_rotation_weight"));
84  *options.mutable_optimization_problem_options() =
86  parameter_dictionary->GetDictionary("optimization_problem").get());
87  options.set_max_num_final_iterations(
88  parameter_dictionary->GetNonNegativeInt("max_num_final_iterations"));
89  CHECK_GT(options.max_num_final_iterations(), 0);
90  options.set_global_sampling_ratio(
91  parameter_dictionary->GetDouble("global_sampling_ratio"));
92  options.set_log_residual_histograms(
93  parameter_dictionary->GetBool("log_residual_histograms"));
94  options.set_global_constraint_search_after_n_seconds(
95  parameter_dictionary->GetDouble(
96  "global_constraint_search_after_n_seconds"));
97  return options;
98 }
99 
100 proto::PoseGraph::Constraint ToProto(const PoseGraph::Constraint& constraint) {
101  proto::PoseGraph::Constraint constraint_proto;
102  *constraint_proto.mutable_relative_pose() =
103  transform::ToProto(constraint.pose.zbar_ij);
104  constraint_proto.set_translation_weight(constraint.pose.translation_weight);
105  constraint_proto.set_rotation_weight(constraint.pose.rotation_weight);
106  constraint_proto.mutable_submap_id()->set_trajectory_id(
107  constraint.submap_id.trajectory_id);
108  constraint_proto.mutable_submap_id()->set_submap_index(
109  constraint.submap_id.submap_index);
110  constraint_proto.mutable_node_id()->set_trajectory_id(
111  constraint.node_id.trajectory_id);
112  constraint_proto.mutable_node_id()->set_node_index(
113  constraint.node_id.node_index);
114  constraint_proto.set_tag(mapping::ToProto(constraint.tag));
115  return constraint_proto;
116 }
117 
118 proto::PoseGraph PoseGraph::ToProto() const {
119  proto::PoseGraph proto;
120 
121  std::map<int, proto::Trajectory* const> trajectory_protos;
122  const auto trajectory = [&proto, &trajectory_protos](
123  const int trajectory_id) -> proto::Trajectory* {
124  if (trajectory_protos.count(trajectory_id) == 0) {
125  auto* const trajectory_proto = proto.add_trajectory();
126  trajectory_proto->set_trajectory_id(trajectory_id);
127  CHECK(trajectory_protos.emplace(trajectory_id, trajectory_proto).second);
128  }
129  return trajectory_protos.at(trajectory_id);
130  };
131 
132  for (const auto& node_id_data : GetTrajectoryNodes()) {
133  CHECK(node_id_data.data.constant_data != nullptr);
134  auto* const node_proto =
135  trajectory(node_id_data.id.trajectory_id)->add_node();
136  node_proto->set_node_index(node_id_data.id.node_index);
137  node_proto->set_timestamp(
138  common::ToUniversal(node_id_data.data.constant_data->time));
139  *node_proto->mutable_pose() =
140  transform::ToProto(node_id_data.data.global_pose);
141  }
142 
143  for (const auto& submap_id_data : GetAllSubmapData()) {
144  CHECK(submap_id_data.data.submap != nullptr);
145  auto* const submap_proto =
146  trajectory(submap_id_data.id.trajectory_id)->add_submap();
147  submap_proto->set_submap_index(submap_id_data.id.submap_index);
148  *submap_proto->mutable_pose() =
149  transform::ToProto(submap_id_data.data.pose);
150  }
151 
152  auto constraints_copy = constraints();
153  proto.mutable_constraint()->Reserve(constraints_copy.size());
154  for (const auto& constraint : constraints_copy) {
155  *proto.add_constraint() = cartographer::mapping::ToProto(constraint);
156  }
157 
158  auto landmarks_copy = GetLandmarkPoses();
159  proto.mutable_landmark_poses()->Reserve(landmarks_copy.size());
160  for (const auto& id_pose : landmarks_copy) {
161  auto* landmark_proto = proto.add_landmark_poses();
162  landmark_proto->set_landmark_id(id_pose.first);
163  *landmark_proto->mutable_global_pose() = transform::ToProto(id_pose.second);
164  }
165  return proto;
166 }
167 
168 } // namespace mapping
169 } // namespace cartographer
PoseGraph::Constraint::Tag FromProto(const proto::PoseGraph::Constraint::Tag &proto)
Definition: pose_graph.cc:38
proto::PoseGraph ToProto() const override
Definition: pose_graph.cc:118
enum cartographer::mapping::PoseGraphInterface::Constraint::Tag tag
virtual std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const =0
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
proto::OptimizationProblemOptions CreateOptimizationProblemOptions(common::LuaParameterDictionary *const parameter_dictionary)
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
Definition: transform.cc:48
proto::PoseGraphOptions CreatePoseGraphOptions(common::LuaParameterDictionary *const parameter_dictionary)
Definition: pose_graph.cc:72
proto::ConstraintBuilderOptions CreateConstraintBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
int64 ToUniversal(const Time time)
Definition: time.cc:36
virtual std::vector< Constraint > constraints() const =0
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
virtual MapById< SubmapId, SubmapData > GetAllSubmapData() const =0
proto::MapLimits ToProto(const MapLimits &map_limits)
Definition: map_limits.h:92
transform::Rigid3d pose
virtual MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const =0


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