serialization_format_migration_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/io/serialization_format_migration.h"
00018 
00019 #include <functional>
00020 #include <memory>
00021 
00022 #include "cartographer/io/internal/in_memory_proto_stream.h"
00023 #include "cartographer/mapping/internal/testing/test_helpers.h"
00024 #include "cartographer/mapping/proto/internal/legacy_serialized_data.pb.h"
00025 #include "cartographer/mapping/proto/pose_graph.pb.h"
00026 #include "cartographer/mapping/proto/serialization.pb.h"
00027 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
00028 #include "cartographer/mapping/trajectory_node.h"
00029 #include "cartographer/transform/transform.h"
00030 #include "gmock/gmock.h"
00031 #include "google/protobuf/text_format.h"
00032 #include "gtest/gtest.h"
00033 
00034 namespace cartographer {
00035 namespace io {
00036 namespace {
00037 
00038 using ::google::protobuf::TextFormat;
00039 using ::testing::Eq;
00040 using ::testing::SizeIs;
00041 
00042 class MigrationTest : public ::testing::Test {
00043  private:
00044   template <class LegacySerializedDataType>
00045   void AddLegacyDataToReader(InMemoryProtoStreamReader& reader) {
00046     mapping::proto::PoseGraph pose_graph;
00047     mapping::proto::AllTrajectoryBuilderOptions all_options;
00048     LegacySerializedDataType submap;
00049     submap.mutable_submap();
00050     LegacySerializedDataType node;
00051     node.mutable_node();
00052     LegacySerializedDataType imu_data;
00053     imu_data.mutable_imu_data();
00054     LegacySerializedDataType odometry_data;
00055     odometry_data.mutable_odometry_data();
00056     LegacySerializedDataType fixed_frame_pose;
00057     fixed_frame_pose.mutable_fixed_frame_pose_data();
00058     LegacySerializedDataType trajectory_data;
00059     trajectory_data.mutable_trajectory_data();
00060     LegacySerializedDataType landmark_data;
00061     landmark_data.mutable_landmark_data();
00062 
00063     reader.AddProto(pose_graph);
00064     reader.AddProto(all_options);
00065     reader.AddProto(submap);
00066     reader.AddProto(node);
00067     reader.AddProto(imu_data);
00068     reader.AddProto(odometry_data);
00069     reader.AddProto(fixed_frame_pose);
00070     reader.AddProto(trajectory_data);
00071     reader.AddProto(landmark_data);
00072   }
00073 
00074  protected:
00075   void SetUp() override {
00076     AddLegacyDataToReader<mapping::proto::LegacySerializedData>(reader_);
00077     AddLegacyDataToReader<mapping::proto::LegacySerializedDataLegacySubmap>(
00078         reader_for_migrating_grid_);
00079 
00080     writer_.reset(new ForwardingProtoStreamWriter(
00081         [this](const google::protobuf::Message* proto) -> bool {
00082           std::string msg_string;
00083           TextFormat::PrintToString(*proto, &msg_string);
00084           this->output_messages_.push_back(msg_string);
00085           return true;
00086         }));
00087     writer_for_migrating_grid_.reset(new ForwardingProtoStreamWriter(
00088         [this](const google::protobuf::Message* proto) -> bool {
00089           std::string msg_string;
00090           TextFormat::PrintToString(*proto, &msg_string);
00091           this->output_messages_after_migrating_grid_.push_back(msg_string);
00092           return true;
00093         }));
00094   }
00095 
00096   InMemoryProtoStreamReader reader_;
00097   InMemoryProtoStreamReader reader_for_migrating_grid_;
00098   std::unique_ptr<ForwardingProtoStreamWriter> writer_;
00099   std::unique_ptr<ForwardingProtoStreamWriter> writer_for_migrating_grid_;
00100   std::vector<std::string> output_messages_;
00101   std::vector<std::string> output_messages_after_migrating_grid_;
00102 
00103   static constexpr int kNumOriginalMessages = 9;
00104 };
00105 
00106 class SubmapHistogramMigrationTest : public ::testing::Test {
00107  protected:
00108   void SetUp() override {
00109     CreateSubmap();
00110     CreateNode();
00111     CreatePoseGraphWithNodeToSubmapConstraint();
00112   }
00113 
00114  private:
00115   void CreateSubmap() {
00116     submap_ = mapping::testing::CreateFakeSubmap3D();
00117     submap_.mutable_submap_3d()->clear_rotational_scan_matcher_histogram();
00118   }
00119 
00120   void CreateNode() {
00121     node_ = mapping::testing::CreateFakeNode();
00122     constexpr int histogram_size = 10;
00123     for (int i = 0; i < histogram_size; ++i) {
00124       node_.mutable_node_data()->add_rotational_scan_matcher_histogram(1.f);
00125     }
00126   }
00127 
00128   void CreatePoseGraphWithNodeToSubmapConstraint() {
00129     mapping::proto::PoseGraph::Constraint* constraint =
00130         pose_graph_.add_constraint();
00131     constraint->set_tag(mapping::proto::PoseGraph::Constraint::INTRA_SUBMAP);
00132     *constraint->mutable_node_id() = node_.node_id();
00133     *constraint->mutable_submap_id() = submap_.submap_id();
00134     *constraint->mutable_relative_pose() =
00135         transform::ToProto(transform::Rigid3d::Identity());
00136   }
00137 
00138  protected:
00139   mapping::proto::PoseGraph pose_graph_;
00140   mapping::proto::Submap submap_;
00141   mapping::proto::Node node_;
00142 };
00143 
00144 TEST_F(MigrationTest, MigrationAddsHeaderAsFirstMessage) {
00145   MigrateStreamFormatToVersion1(&reader_, writer_.get(),
00146                                 false /* migrate_grid_format */);
00147   // We expect one message more than the original number of messages, because of
00148   // the added header.
00149   EXPECT_THAT(output_messages_, SizeIs(kNumOriginalMessages + 1));
00150 
00151   mapping::proto::SerializationHeader header;
00152   EXPECT_TRUE(TextFormat::ParseFromString(output_messages_[0], &header));
00153   EXPECT_THAT(header.format_version(), Eq(1));
00154 }
00155 
00156 TEST_F(MigrationTest, MigrationWithGridMigrationAddsHeaderAsFirstMessage) {
00157   MigrateStreamFormatToVersion1(&reader_for_migrating_grid_,
00158                                 writer_for_migrating_grid_.get(),
00159                                 true /* migrate_grid_format */);
00160   // We expect one message more than the original number of messages, because of
00161   // the added header.
00162   EXPECT_THAT(output_messages_after_migrating_grid_,
00163               SizeIs(kNumOriginalMessages + 1));
00164 
00165   mapping::proto::SerializationHeader header;
00166   EXPECT_TRUE(TextFormat::ParseFromString(
00167       output_messages_after_migrating_grid_[0], &header));
00168   EXPECT_THAT(header.format_version(), Eq(1));
00169 }
00170 
00171 TEST_F(MigrationTest, SerializedDataOrderIsCorrect) {
00172   MigrateStreamFormatToVersion1(&reader_, writer_.get(),
00173                                 false /* migrate_grid_format */);
00174   EXPECT_THAT(output_messages_, SizeIs(kNumOriginalMessages + 1));
00175 
00176   std::vector<mapping::proto::SerializedData> serialized(
00177       output_messages_.size() - 1);
00178   for (size_t i = 1; i < output_messages_.size(); ++i) {
00179     EXPECT_TRUE(
00180         TextFormat::ParseFromString(output_messages_[i], &serialized[i - 1]));
00181   }
00182 
00183   EXPECT_TRUE(serialized[0].has_pose_graph());
00184   EXPECT_TRUE(serialized[1].has_all_trajectory_builder_options());
00185   EXPECT_TRUE(serialized[2].has_submap());
00186   EXPECT_TRUE(serialized[3].has_node());
00187   EXPECT_TRUE(serialized[4].has_trajectory_data());
00188   EXPECT_TRUE(serialized[5].has_imu_data());
00189   EXPECT_TRUE(serialized[6].has_odometry_data());
00190   EXPECT_TRUE(serialized[7].has_fixed_frame_pose_data());
00191   EXPECT_TRUE(serialized[8].has_landmark_data());
00192 }
00193 
00194 TEST_F(MigrationTest, SerializedDataOrderAfterGridMigrationIsCorrect) {
00195   MigrateStreamFormatToVersion1(&reader_for_migrating_grid_,
00196                                 writer_for_migrating_grid_.get(),
00197                                 true /* migrate_grid_format */);
00198   EXPECT_THAT(output_messages_after_migrating_grid_,
00199               SizeIs(kNumOriginalMessages + 1));
00200 
00201   std::vector<mapping::proto::SerializedData> serialized(
00202       output_messages_after_migrating_grid_.size() - 1);
00203   for (size_t i = 1; i < output_messages_after_migrating_grid_.size(); ++i) {
00204     EXPECT_TRUE(TextFormat::ParseFromString(
00205         output_messages_after_migrating_grid_[i], &serialized[i - 1]));
00206   }
00207 
00208   EXPECT_TRUE(serialized[0].has_pose_graph());
00209   EXPECT_TRUE(serialized[1].has_all_trajectory_builder_options());
00210   EXPECT_TRUE(serialized[2].has_submap());
00211   EXPECT_TRUE(serialized[3].has_node());
00212   EXPECT_TRUE(serialized[4].has_trajectory_data());
00213   EXPECT_TRUE(serialized[5].has_imu_data());
00214   EXPECT_TRUE(serialized[6].has_odometry_data());
00215   EXPECT_TRUE(serialized[7].has_fixed_frame_pose_data());
00216   EXPECT_TRUE(serialized[8].has_landmark_data());
00217 }
00218 
00219 TEST_F(SubmapHistogramMigrationTest,
00220        SubmapHistogramGenerationFromTrajectoryNodes) {
00221   mapping::MapById<mapping::SubmapId, mapping::proto::Submap>
00222       submap_id_to_submap;
00223   mapping::SubmapId submap_id(submap_.submap_id().trajectory_id(),
00224                               submap_.submap_id().submap_index());
00225   submap_id_to_submap.Insert(submap_id, submap_);
00226 
00227   mapping::MapById<mapping::NodeId, mapping::proto::Node> node_id_to_node;
00228   mapping::NodeId node_id(node_.node_id().trajectory_id(),
00229                           node_.node_id().node_index());
00230   node_id_to_node.Insert(node_id, node_);
00231 
00232   const auto submap_id_to_submap_migrated =
00233       MigrateSubmapFormatVersion1ToVersion2(submap_id_to_submap,
00234                                             node_id_to_node, pose_graph_);
00235 
00236   EXPECT_EQ(submap_id_to_submap_migrated.size(), submap_id_to_submap.size());
00237   const mapping::proto::Submap& migrated_submap =
00238       submap_id_to_submap_migrated.at(submap_id);
00239 
00240   EXPECT_FALSE(migrated_submap.has_submap_2d());
00241   EXPECT_TRUE(migrated_submap.has_submap_3d());
00242   const mapping::proto::Submap3D& migrated_submap_3d =
00243       migrated_submap.submap_3d();
00244   const mapping::proto::TrajectoryNodeData& node_data = node_.node_data();
00245   EXPECT_EQ(migrated_submap_3d.rotational_scan_matcher_histogram_size(),
00246             node_data.rotational_scan_matcher_histogram_size());
00247   for (int i = 0; i < node_data.rotational_scan_matcher_histogram_size(); ++i) {
00248     EXPECT_EQ(migrated_submap_3d.rotational_scan_matcher_histogram(i),
00249               node_data.rotational_scan_matcher_histogram(i));
00250   }
00251 }
00252 
00253 }  // namespace
00254 }  // namespace io
00255 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:36