mapping_state_serialization.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 #include "cartographer/mapping/proto/serialization.pb.h"
20 
21 namespace cartographer {
22 namespace io {
23 namespace {
24 using mapping::MapById;
25 using mapping::NodeId;
26 using mapping::PoseGraphInterface;
27 using mapping::SubmapId;
28 using mapping::TrajectoryNode;
29 using mapping::proto::SerializedData;
30 
31 mapping::proto::AllTrajectoryBuilderOptions
32 CreateAllTrajectoryBuilderOptionsProto(
33  const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
34  all_options_with_sensor_ids) {
35  mapping::proto::AllTrajectoryBuilderOptions all_options_proto;
36  for (const auto& options_with_sensor_ids : all_options_with_sensor_ids) {
37  *all_options_proto.add_options_with_sensor_ids() = options_with_sensor_ids;
38  }
39  CHECK_EQ(all_options_with_sensor_ids.size(),
40  all_options_proto.options_with_sensor_ids_size());
41  return all_options_proto;
42 }
43 
44 mapping::proto::SerializationHeader CreateHeader() {
45  mapping::proto::SerializationHeader header;
46  header.set_format_version(kMappingStateSerializationFormatVersion);
47  return header;
48 }
49 
50 SerializedData SerializePoseGraph(const mapping::PoseGraph& pose_graph) {
51  SerializedData proto;
52  *proto.mutable_pose_graph() = pose_graph.ToProto();
53  return proto;
54 }
55 
56 SerializedData SerializeAllTrajectoryBuilderOptions(
57  const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
58  trajectory_builder_options) {
59  SerializedData proto;
60  *proto.mutable_all_trajectory_builder_options() =
61  CreateAllTrajectoryBuilderOptionsProto(trajectory_builder_options);
62  return proto;
63 }
64 
65 void SerializeSubmaps(
66  const MapById<SubmapId, PoseGraphInterface::SubmapData>& submap_data,
67  ProtoStreamWriterInterface* const writer) {
68  SerializedData proto;
69  // Next serialize all submaps.
70  for (const auto& submap_id_data : submap_data) {
71  auto* const submap_proto = proto.mutable_submap();
72  submap_proto->mutable_submap_id()->set_trajectory_id(
73  submap_id_data.id.trajectory_id);
74  submap_proto->mutable_submap_id()->set_submap_index(
75  submap_id_data.id.submap_index);
76  submap_id_data.data.submap->ToProto(submap_proto,
77  /*include_probability_grid_data=*/true);
78  writer->WriteProto(proto);
79  }
80 }
81 
82 void SerializeTrajectoryNodes(
83  const MapById<NodeId, TrajectoryNode>& trajectory_nodes,
84  ProtoStreamWriterInterface* const writer) {
85  SerializedData proto;
86  for (const auto& node_id_data : trajectory_nodes) {
87  auto* const node_proto = proto.mutable_node();
88  node_proto->mutable_node_id()->set_trajectory_id(
89  node_id_data.id.trajectory_id);
90  node_proto->mutable_node_id()->set_node_index(node_id_data.id.node_index);
91  *node_proto->mutable_node_data() =
92  ToProto(*node_id_data.data.constant_data);
93  writer->WriteProto(proto);
94  }
95 }
96 
97 void SerializeTrajectoryData(
98  const std::map<int, PoseGraphInterface::TrajectoryData>&
99  all_trajectory_data,
100  ProtoStreamWriterInterface* const writer) {
101  SerializedData proto;
102  for (const auto& trajectory_data : all_trajectory_data) {
103  auto* const trajectory_data_proto = proto.mutable_trajectory_data();
104  trajectory_data_proto->set_trajectory_id(trajectory_data.first);
105  trajectory_data_proto->set_gravity_constant(
106  trajectory_data.second.gravity_constant);
107  *trajectory_data_proto->mutable_imu_calibration() = transform::ToProto(
108  Eigen::Quaterniond(trajectory_data.second.imu_calibration[0],
109  trajectory_data.second.imu_calibration[1],
110  trajectory_data.second.imu_calibration[2],
111  trajectory_data.second.imu_calibration[3]));
112  if (trajectory_data.second.fixed_frame_origin_in_map.has_value()) {
113  *trajectory_data_proto->mutable_fixed_frame_origin_in_map() =
115  trajectory_data.second.fixed_frame_origin_in_map.value());
116  }
117  writer->WriteProto(proto);
118  }
119 }
120 
121 void SerializeImuData(const sensor::MapByTime<sensor::ImuData>& all_imu_data,
122  ProtoStreamWriterInterface* const writer) {
123  SerializedData proto;
124  for (const int trajectory_id : all_imu_data.trajectory_ids()) {
125  for (const auto& imu_data : all_imu_data.trajectory(trajectory_id)) {
126  auto* const imu_data_proto = proto.mutable_imu_data();
127  imu_data_proto->set_trajectory_id(trajectory_id);
128  *imu_data_proto->mutable_imu_data() = sensor::ToProto(imu_data);
129  writer->WriteProto(proto);
130  }
131  }
132 }
133 
134 void SerializeOdometryData(
135  const sensor::MapByTime<sensor::OdometryData>& all_odometry_data,
136  ProtoStreamWriterInterface* const writer) {
137  SerializedData proto;
138  for (const int trajectory_id : all_odometry_data.trajectory_ids()) {
139  for (const auto& odometry_data :
140  all_odometry_data.trajectory(trajectory_id)) {
141  auto* const odometry_data_proto = proto.mutable_odometry_data();
142  odometry_data_proto->set_trajectory_id(trajectory_id);
143  *odometry_data_proto->mutable_odometry_data() =
144  sensor::ToProto(odometry_data);
145  writer->WriteProto(proto);
146  }
147  }
148 }
149 
150 void SerializeFixedFramePoseData(
151  const sensor::MapByTime<sensor::FixedFramePoseData>&
152  all_fixed_frame_pose_data,
153  ProtoStreamWriterInterface* const writer) {
154  SerializedData proto;
155  for (const int trajectory_id : all_fixed_frame_pose_data.trajectory_ids()) {
156  for (const auto& fixed_frame_pose_data :
157  all_fixed_frame_pose_data.trajectory(trajectory_id)) {
158  auto* const fixed_frame_pose_data_proto =
159  proto.mutable_fixed_frame_pose_data();
160  fixed_frame_pose_data_proto->set_trajectory_id(trajectory_id);
161  *fixed_frame_pose_data_proto->mutable_fixed_frame_pose_data() =
162  sensor::ToProto(fixed_frame_pose_data);
163  writer->WriteProto(proto);
164  }
165  }
166 }
167 
168 void SerializeLandmarkNodes(
169  const std::map<std::string, PoseGraphInterface::LandmarkNode>&
170  all_landmark_nodes,
171  ProtoStreamWriterInterface* const writer) {
172  SerializedData proto;
173  for (const auto& node : all_landmark_nodes) {
174  for (const auto& observation : node.second.landmark_observations) {
175  auto* landmark_data_proto = proto.mutable_landmark_data();
176  landmark_data_proto->set_trajectory_id(observation.trajectory_id);
177  landmark_data_proto->mutable_landmark_data()->set_timestamp(
178  common::ToUniversal(observation.time));
179  auto* observation_proto = landmark_data_proto->mutable_landmark_data()
180  ->add_landmark_observations();
181  observation_proto->set_id(node.first);
182  *observation_proto->mutable_landmark_to_tracking_transform() =
183  transform::ToProto(observation.landmark_to_tracking_transform);
184  observation_proto->set_translation_weight(observation.translation_weight);
185  observation_proto->set_rotation_weight(observation.rotation_weight);
186  writer->WriteProto(proto);
187  }
188  }
189 }
190 
191 } // namespace
192 
194  const mapping::PoseGraph& pose_graph,
195  const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
196  trajectory_builder_options,
197  ProtoStreamWriterInterface* const writer) {
198  writer->WriteProto(CreateHeader());
199  writer->WriteProto(SerializePoseGraph(pose_graph));
200  writer->WriteProto(
201  SerializeAllTrajectoryBuilderOptions(trajectory_builder_options));
202 
203  SerializeSubmaps(pose_graph.GetAllSubmapData(), writer);
204  SerializeTrajectoryNodes(pose_graph.GetTrajectoryNodes(), writer);
205  SerializeTrajectoryData(pose_graph.GetTrajectoryData(), writer);
206  SerializeImuData(pose_graph.GetImuData(), writer);
207  SerializeOdometryData(pose_graph.GetOdometryData(), writer);
208  SerializeFixedFramePoseData(pose_graph.GetFixedFramePoseData(), writer);
209  SerializeLandmarkNodes(pose_graph.GetLandmarkNodes(), writer);
210 }
211 
212 } // namespace io
213 } // namespace cartographer
virtual sensor::MapByTime< sensor::ImuData > GetImuData() const =0
void WritePbStream(const mapping::PoseGraph &pose_graph, const std::vector< mapping::proto::TrajectoryBuilderOptionsWithSensorIds > &trajectory_builder_options, ProtoStreamWriterInterface *const writer)
virtual sensor::MapByTime< sensor::FixedFramePoseData > GetFixedFramePoseData() const =0
proto::FixedFramePoseData ToProto(const FixedFramePoseData &pose_data)
static constexpr int kMappingStateSerializationFormatVersion
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
Definition: transform.cc:48
virtual std::map< int, TrajectoryData > GetTrajectoryData() const =0
int64 ToUniversal(const Time time)
Definition: time.cc:36
virtual std::map< std::string, PoseGraph::LandmarkNode > GetLandmarkNodes() const =0
virtual MapById< SubmapId, SubmapData > GetAllSubmapData() const =0
virtual void WriteProto(const google::protobuf::Message &proto)=0
proto::SensorId ToProto(const mapping::TrajectoryBuilderInterface::SensorId &sensor_id)
virtual MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const =0
virtual sensor::MapByTime< sensor::OdometryData > GetOdometryData() const =0


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