serialization_format_migration.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 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 
19 #include <unordered_map>
20 #include <vector>
21 
22 #include "cartographer/mapping/proto/internal/legacy_serialized_data.pb.h"
23 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
24 #include "glog/logging.h"
25 
26 namespace cartographer {
27 namespace io {
28 namespace {
29 
30 using mapping::proto::SerializedData;
31 using ProtoMap = std::unordered_map<int, std::vector<SerializedData>>;
32 
33 bool ReadPoseGraph(cartographer::io::ProtoStreamReaderInterface* const input,
34  ProtoMap* proto_map) {
35  auto& pose_graph_vec = (*proto_map)[SerializedData::kPoseGraph];
36  pose_graph_vec.emplace_back();
37  return input->ReadProto(pose_graph_vec.back().mutable_pose_graph());
38 }
39 
40 bool ReadBuilderOptions(
42  ProtoMap* proto_map) {
43  auto& options_vec =
44  (*proto_map)[SerializedData::kAllTrajectoryBuilderOptions];
45  options_vec.emplace_back();
46  return input->ReadProto(
47  options_vec.back().mutable_all_trajectory_builder_options());
48 }
49 
50 bool DeserializeNext(cartographer::io::ProtoStreamReaderInterface* const input,
51  ProtoMap* proto_map) {
52  mapping::proto::LegacySerializedData legacy_data;
53  if (!input->ReadProto(&legacy_data)) return false;
54 
55  if (legacy_data.has_submap()) {
56  auto& output_vector = (*proto_map)[SerializedData::kSubmapFieldNumber];
57  output_vector.emplace_back();
58  *output_vector.back().mutable_submap() = legacy_data.submap();
59  }
60  if (legacy_data.has_node()) {
61  auto& output_vector = (*proto_map)[SerializedData::kNodeFieldNumber];
62  output_vector.emplace_back();
63  *output_vector.back().mutable_node() = legacy_data.node();
64  }
65  if (legacy_data.has_trajectory_data()) {
66  auto& output_vector =
67  (*proto_map)[SerializedData::kTrajectoryDataFieldNumber];
68  output_vector.emplace_back();
69  *output_vector.back().mutable_trajectory_data() =
70  legacy_data.trajectory_data();
71  }
72  if (legacy_data.has_imu_data()) {
73  auto& output_vector = (*proto_map)[SerializedData::kImuDataFieldNumber];
74  output_vector.emplace_back();
75  *output_vector.back().mutable_imu_data() = legacy_data.imu_data();
76  }
77  if (legacy_data.has_odometry_data()) {
78  auto& output_vector = (*proto_map)[SerializedData::kOdometryData];
79  output_vector.emplace_back();
80  *output_vector.back().mutable_odometry_data() = legacy_data.odometry_data();
81  }
82  if (legacy_data.has_fixed_frame_pose_data()) {
83  auto& output_vector =
84  (*proto_map)[SerializedData::kFixedFramePoseDataFieldNumber];
85  output_vector.emplace_back();
86  *output_vector.back().mutable_fixed_frame_pose_data() =
87  legacy_data.fixed_frame_pose_data();
88  }
89  if (legacy_data.has_landmark_data()) {
90  auto& output_vector =
91  (*proto_map)[SerializedData::kLandmarkDataFieldNumber];
92  output_vector.emplace_back();
93  *output_vector.back().mutable_landmark_data() = legacy_data.landmark_data();
94  }
95  return true;
96 }
97 
98 ProtoMap ParseLegacyData(
100  ProtoMap proto_map;
101  CHECK(ReadPoseGraph(input, &proto_map))
102  << "Input stream seems to differ from original stream format. Could "
103  "not "
104  "read PoseGraph as first message.";
105  CHECK(ReadBuilderOptions(input, &proto_map))
106  << "Input stream seems to differ from original stream format. Could "
107  "not "
108  "read AllTrajectoryBuilderOptions as second message.";
109  do {
110  } while (DeserializeNext(input, &proto_map));
111  return proto_map;
112 }
113 
114 mapping::proto::SerializationHeader CreateSerializationHeader() {
115  constexpr uint32_t kVersion1 = 1;
116  mapping::proto::SerializationHeader header;
117  header.set_format_version(kVersion1);
118  return header;
119 }
120 
121 void SerializeToVersion1Format(
122  const ProtoMap& deserialized_data,
124  const std::vector<int> kFieldSerializationOrder = {
125  SerializedData::kPoseGraphFieldNumber,
126  SerializedData::kAllTrajectoryBuilderOptionsFieldNumber,
127  SerializedData::kSubmapFieldNumber,
128  SerializedData::kNodeFieldNumber,
129  SerializedData::kTrajectoryDataFieldNumber,
130  SerializedData::kImuDataFieldNumber,
131  SerializedData::kOdometryDataFieldNumber,
132  SerializedData::kFixedFramePoseDataFieldNumber,
133  SerializedData::kLandmarkDataFieldNumber};
134 
135  output->WriteProto(CreateSerializationHeader());
136  for (auto field_index : kFieldSerializationOrder) {
137  const auto proto_vector_it = deserialized_data.find(field_index);
138  if (proto_vector_it == deserialized_data.end()) continue;
139  for (const auto& proto : proto_vector_it->second) {
140  output->WriteProto(proto);
141  }
142  }
143 }
144 } // namespace
145 
149  SerializeToVersion1Format(ParseLegacyData(input), output);
150 }
151 
152 } // namespace io
153 } // namespace cartographer
void MigrateStreamFormatToVersion1(cartographer::io::ProtoStreamReaderInterface *const input, cartographer::io::ProtoStreamWriterInterface *const output)
virtual bool ReadProto(google::protobuf::Message *proto)=0
virtual void WriteProto(const google::protobuf::Message &proto)=0


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