map_builder_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 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/mapping/map_builder.h"
00018 
00019 #include "cartographer/common/config.h"
00020 #include "cartographer/io/proto_stream.h"
00021 #include "cartographer/mapping/2d/grid_2d.h"
00022 #include "cartographer/mapping/internal/testing/test_helpers.h"
00023 #include "gmock/gmock.h"
00024 #include "gtest/gtest.h"
00025 
00026 namespace cartographer {
00027 namespace mapping {
00028 namespace {
00029 
00030 using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
00031 
00032 const SensorId kRangeSensorId{SensorId::SensorType::RANGE, "range"};
00033 const SensorId kIMUSensorId{SensorId::SensorType::IMU, "imu"};
00034 constexpr double kDuration = 4.;         // Seconds.
00035 constexpr double kTimeStep = 0.1;        // Seconds.
00036 constexpr double kTravelDistance = 1.2;  // Meters.
00037 
00038 template <class T>
00039 class MapBuilderTestBase : public T {
00040  protected:
00041   void SetUp() override {
00042     // Global SLAM optimization is not executed.
00043     const std::string kMapBuilderLua = R"text(
00044       include "map_builder.lua"
00045       MAP_BUILDER.use_trajectory_builder_2d = true
00046       MAP_BUILDER.pose_graph.optimize_every_n_nodes = 0
00047       MAP_BUILDER.pose_graph.global_sampling_ratio = 0.05
00048       MAP_BUILDER.pose_graph.global_constraint_search_after_n_seconds = 0
00049       return MAP_BUILDER)text";
00050     auto map_builder_parameters = testing::ResolveLuaParameters(kMapBuilderLua);
00051     map_builder_options_ =
00052         CreateMapBuilderOptions(map_builder_parameters.get());
00053     // Multiple submaps are created because of a small 'num_range_data'.
00054     const std::string kTrajectoryBuilderLua = R"text(
00055       include "trajectory_builder.lua"
00056       TRAJECTORY_BUILDER.trajectory_builder_2d.use_imu_data = false
00057       TRAJECTORY_BUILDER.trajectory_builder_2d.submaps.num_range_data = 4
00058       TRAJECTORY_BUILDER.trajectory_builder_3d.submaps.num_range_data = 4
00059       return TRAJECTORY_BUILDER)text";
00060     auto trajectory_builder_parameters =
00061         testing::ResolveLuaParameters(kTrajectoryBuilderLua);
00062     trajectory_builder_options_ =
00063         CreateTrajectoryBuilderOptions(trajectory_builder_parameters.get());
00064   }
00065 
00066   void BuildMapBuilder() {
00067     map_builder_ = absl::make_unique<MapBuilder>(map_builder_options_);
00068   }
00069 
00070   void SetOptionsTo3D() {
00071     map_builder_options_.set_use_trajectory_builder_2d(false);
00072     map_builder_options_.set_use_trajectory_builder_3d(true);
00073   }
00074 
00075   void SetOptionsToTSDF2D() {
00076     trajectory_builder_options_.mutable_trajectory_builder_2d_options()
00077         ->mutable_submaps_options()
00078         ->mutable_range_data_inserter_options()
00079         ->set_range_data_inserter_type(
00080             proto::RangeDataInserterOptions::TSDF_INSERTER_2D);
00081     trajectory_builder_options_.mutable_trajectory_builder_2d_options()
00082         ->mutable_submaps_options()
00083         ->mutable_grid_options_2d()
00084         ->set_grid_type(proto::GridOptions2D::TSDF);
00085     trajectory_builder_options_.mutable_trajectory_builder_2d_options()
00086         ->mutable_ceres_scan_matcher_options()
00087         ->set_occupied_space_weight(10.0);
00088     map_builder_options_.mutable_pose_graph_options()
00089         ->mutable_constraint_builder_options()
00090         ->mutable_ceres_scan_matcher_options()
00091         ->set_occupied_space_weight(50.0);
00092   }
00093 
00094   void SetOptionsEnableGlobalOptimization() {
00095     map_builder_options_.mutable_pose_graph_options()
00096         ->set_optimize_every_n_nodes(3);
00097     trajectory_builder_options_.mutable_trajectory_builder_2d_options()
00098         ->mutable_motion_filter_options()
00099         ->set_max_distance_meters(0);
00100   }
00101 
00102   MapBuilderInterface::LocalSlamResultCallback GetLocalSlamResultCallback() {
00103     return [=](const int trajectory_id, const ::cartographer::common::Time time,
00104                const ::cartographer::transform::Rigid3d local_pose,
00105                ::cartographer::sensor::RangeData range_data_in_local,
00106                const std::unique_ptr<
00107                    const cartographer::mapping::TrajectoryBuilderInterface::
00108                        InsertionResult>) {
00109       local_slam_result_poses_.push_back(local_pose);
00110     };
00111   }
00112 
00113   int CreateTrajectoryWithFakeData(double timestamps_add_duration = 0.) {
00114     int trajectory_id = map_builder_->AddTrajectoryBuilder(
00115         {kRangeSensorId}, trajectory_builder_options_,
00116         GetLocalSlamResultCallback());
00117     TrajectoryBuilderInterface* trajectory_builder =
00118         map_builder_->GetTrajectoryBuilder(trajectory_id);
00119     auto measurements = testing::GenerateFakeRangeMeasurements(
00120         kTravelDistance, kDuration, kTimeStep);
00121     for (auto& measurement : measurements) {
00122       measurement.time += common::FromSeconds(timestamps_add_duration);
00123       trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00124     }
00125     map_builder_->FinishTrajectory(trajectory_id);
00126     return trajectory_id;
00127   }
00128 
00129   std::unique_ptr<MapBuilderInterface> map_builder_;
00130   proto::MapBuilderOptions map_builder_options_;
00131   proto::TrajectoryBuilderOptions trajectory_builder_options_;
00132   std::vector<::cartographer::transform::Rigid3d> local_slam_result_poses_;
00133 };
00134 
00135 class MapBuilderTest : public MapBuilderTestBase<::testing::Test> {};
00136 class MapBuilderTestByGridType
00137     : public MapBuilderTestBase<::testing::TestWithParam<GridType>> {};
00138 class MapBuilderTestByGridTypeAndDimensions
00139     : public MapBuilderTestBase<
00140           ::testing::TestWithParam<std::pair<GridType, int /* dimensions */>>> {
00141 };
00142 INSTANTIATE_TEST_CASE_P(MapBuilderTestByGridType, MapBuilderTestByGridType,
00143                         ::testing::Values(GridType::PROBABILITY_GRID,
00144                                           GridType::TSDF));
00145 INSTANTIATE_TEST_CASE_P(
00146     MapBuilderTestByGridTypeAndDimensions,
00147     MapBuilderTestByGridTypeAndDimensions,
00148     ::testing::Values(std::make_pair(GridType::PROBABILITY_GRID, 2),
00149                       std::make_pair(GridType::PROBABILITY_GRID, 3),
00150                       std::make_pair(GridType::TSDF, 2)));
00151 
00152 TEST_P(MapBuilderTestByGridTypeAndDimensions, TrajectoryAddFinish) {
00153   if (GetParam().second == 3) SetOptionsTo3D();
00154   if (GetParam().first == GridType::TSDF) SetOptionsToTSDF2D();
00155   BuildMapBuilder();
00156   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00157       {kRangeSensorId}, trajectory_builder_options_,
00158       nullptr /* GetLocalSlamResultCallbackForSubscriptions */);
00159   EXPECT_EQ(1, map_builder_->num_trajectory_builders());
00160   EXPECT_TRUE(map_builder_->GetTrajectoryBuilder(trajectory_id) != nullptr);
00161   EXPECT_TRUE(map_builder_->pose_graph() != nullptr);
00162   map_builder_->FinishTrajectory(trajectory_id);
00163   map_builder_->pose_graph()->RunFinalOptimization();
00164   EXPECT_TRUE(map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
00165 }
00166 
00167 TEST_P(MapBuilderTestByGridType, LocalSlam2D) {
00168   if (GetParam() == GridType::TSDF) SetOptionsToTSDF2D();
00169   BuildMapBuilder();
00170   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00171       {kRangeSensorId}, trajectory_builder_options_,
00172       GetLocalSlamResultCallback());
00173   TrajectoryBuilderInterface* trajectory_builder =
00174       map_builder_->GetTrajectoryBuilder(trajectory_id);
00175   const auto measurements = testing::GenerateFakeRangeMeasurements(
00176       kTravelDistance, kDuration, kTimeStep);
00177   for (const auto& measurement : measurements) {
00178     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00179   }
00180   map_builder_->FinishTrajectory(trajectory_id);
00181   map_builder_->pose_graph()->RunFinalOptimization();
00182   EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
00183   EXPECT_NEAR(kTravelDistance,
00184               (local_slam_result_poses_.back().translation() -
00185                local_slam_result_poses_.front().translation())
00186                   .norm(),
00187               0.1 * kTravelDistance);
00188 }
00189 
00190 TEST_F(MapBuilderTest, LocalSlam3D) {
00191   SetOptionsTo3D();
00192   BuildMapBuilder();
00193   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00194       {kRangeSensorId, kIMUSensorId}, trajectory_builder_options_,
00195       GetLocalSlamResultCallback());
00196   TrajectoryBuilderInterface* trajectory_builder =
00197       map_builder_->GetTrajectoryBuilder(trajectory_id);
00198   const auto measurements = testing::GenerateFakeRangeMeasurements(
00199       kTravelDistance, kDuration, kTimeStep);
00200   for (const auto& measurement : measurements) {
00201     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00202     trajectory_builder->AddSensorData(
00203         kIMUSensorId.id,
00204         sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
00205                         Eigen::Vector3d::Zero()});
00206   }
00207   map_builder_->FinishTrajectory(trajectory_id);
00208   map_builder_->pose_graph()->RunFinalOptimization();
00209   EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
00210   EXPECT_NEAR(kTravelDistance,
00211               (local_slam_result_poses_.back().translation() -
00212                local_slam_result_poses_.front().translation())
00213                   .norm(),
00214               0.1 * kTravelDistance);
00215 }
00216 
00217 TEST_P(MapBuilderTestByGridType, GlobalSlam2D) {
00218   if (GetParam() == GridType::TSDF) SetOptionsToTSDF2D();
00219   SetOptionsEnableGlobalOptimization();
00220   BuildMapBuilder();
00221   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00222       {kRangeSensorId}, trajectory_builder_options_,
00223       GetLocalSlamResultCallback());
00224   TrajectoryBuilderInterface* trajectory_builder =
00225       map_builder_->GetTrajectoryBuilder(trajectory_id);
00226   const auto measurements = testing::GenerateFakeRangeMeasurements(
00227       kTravelDistance, kDuration, kTimeStep);
00228   for (const auto& measurement : measurements) {
00229     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00230   }
00231   map_builder_->FinishTrajectory(trajectory_id);
00232   map_builder_->pose_graph()->RunFinalOptimization();
00233   EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
00234   EXPECT_NEAR(kTravelDistance,
00235               (local_slam_result_poses_.back().translation() -
00236                local_slam_result_poses_.front().translation())
00237                   .norm(),
00238               0.1 * kTravelDistance);
00239   EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 50);
00240   EXPECT_THAT(map_builder_->pose_graph()->constraints(),
00241               ::testing::Contains(::testing::Field(
00242                   &PoseGraphInterface::Constraint::tag,
00243                   PoseGraphInterface::Constraint::INTER_SUBMAP)));
00244   const auto trajectory_nodes =
00245       map_builder_->pose_graph()->GetTrajectoryNodes();
00246   EXPECT_GE(trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 20);
00247   const auto submap_data = map_builder_->pose_graph()->GetAllSubmapData();
00248   EXPECT_GE(submap_data.SizeOfTrajectoryOrZero(trajectory_id), 5);
00249   const transform::Rigid3d final_pose =
00250       map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
00251       local_slam_result_poses_.back();
00252   EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
00253               0.1 * kTravelDistance);
00254 }
00255 
00256 TEST_F(MapBuilderTest, GlobalSlam3D) {
00257   SetOptionsTo3D();
00258   SetOptionsEnableGlobalOptimization();
00259   BuildMapBuilder();
00260   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00261       {kRangeSensorId, kIMUSensorId}, trajectory_builder_options_,
00262       GetLocalSlamResultCallback());
00263   TrajectoryBuilderInterface* trajectory_builder =
00264       map_builder_->GetTrajectoryBuilder(trajectory_id);
00265   const auto measurements = testing::GenerateFakeRangeMeasurements(
00266       kTravelDistance, kDuration, kTimeStep);
00267   for (const auto& measurement : measurements) {
00268     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00269     trajectory_builder->AddSensorData(
00270         kIMUSensorId.id,
00271         sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
00272                         Eigen::Vector3d::Zero()});
00273   }
00274   map_builder_->FinishTrajectory(trajectory_id);
00275   map_builder_->pose_graph()->RunFinalOptimization();
00276   EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
00277   EXPECT_NEAR(kTravelDistance,
00278               (local_slam_result_poses_.back().translation() -
00279                local_slam_result_poses_.front().translation())
00280                   .norm(),
00281               0.1 * kTravelDistance);
00282   EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 10);
00283   EXPECT_THAT(map_builder_->pose_graph()->constraints(),
00284               ::testing::Contains(::testing::Field(
00285                   &PoseGraphInterface::Constraint::tag,
00286                   PoseGraphInterface::Constraint::INTER_SUBMAP)));
00287   const auto trajectory_nodes =
00288       map_builder_->pose_graph()->GetTrajectoryNodes();
00289   EXPECT_GE(trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 5);
00290   const auto submap_data = map_builder_->pose_graph()->GetAllSubmapData();
00291   EXPECT_GE(submap_data.SizeOfTrajectoryOrZero(trajectory_id), 2);
00292   const transform::Rigid3d final_pose =
00293       map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
00294       local_slam_result_poses_.back();
00295   EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
00296               0.1 * kTravelDistance);
00297 }
00298 
00299 TEST_P(MapBuilderTestByGridType, DeleteFinishedTrajectory2D) {
00300   if (GetParam() == GridType::TSDF) SetOptionsToTSDF2D();
00301   SetOptionsEnableGlobalOptimization();
00302   BuildMapBuilder();
00303   int trajectory_id = CreateTrajectoryWithFakeData();
00304   map_builder_->pose_graph()->RunFinalOptimization();
00305   EXPECT_TRUE(map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
00306   EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 50);
00307   EXPECT_GE(
00308       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00309           trajectory_id),
00310       20);
00311   EXPECT_GE(
00312       map_builder_->pose_graph()->GetAllSubmapData().SizeOfTrajectoryOrZero(
00313           trajectory_id),
00314       5);
00315   map_builder_->pose_graph()->DeleteTrajectory(trajectory_id);
00316   int another_trajectory_id = CreateTrajectoryWithFakeData(100.);
00317   map_builder_->pose_graph()->RunFinalOptimization();
00318   EXPECT_TRUE(
00319       map_builder_->pose_graph()->IsTrajectoryFinished(another_trajectory_id));
00320   EXPECT_EQ(
00321       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00322           trajectory_id),
00323       0);
00324   EXPECT_EQ(
00325       map_builder_->pose_graph()->GetAllSubmapData().SizeOfTrajectoryOrZero(
00326           trajectory_id),
00327       0);
00328   map_builder_->pose_graph()->DeleteTrajectory(another_trajectory_id);
00329   map_builder_->pose_graph()->RunFinalOptimization();
00330   EXPECT_EQ(map_builder_->pose_graph()->constraints().size(), 0);
00331   EXPECT_EQ(
00332       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00333           another_trajectory_id),
00334       0);
00335   EXPECT_EQ(
00336       map_builder_->pose_graph()->GetAllSubmapData().SizeOfTrajectoryOrZero(
00337           another_trajectory_id),
00338       0);
00339 }
00340 
00341 TEST_P(MapBuilderTestByGridTypeAndDimensions, SaveLoadState) {
00342   if (GetParam().second == 3) SetOptionsTo3D();
00343   if (GetParam().first == GridType::TSDF) SetOptionsToTSDF2D();
00344   trajectory_builder_options_.mutable_trajectory_builder_2d_options()
00345       ->set_use_imu_data(true);
00346   BuildMapBuilder();
00347   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00348       {kRangeSensorId, kIMUSensorId}, trajectory_builder_options_,
00349       GetLocalSlamResultCallback());
00350   TrajectoryBuilderInterface* trajectory_builder =
00351       map_builder_->GetTrajectoryBuilder(trajectory_id);
00352   const auto measurements = testing::GenerateFakeRangeMeasurements(
00353       kTravelDistance, kDuration, kTimeStep);
00354   for (const auto& measurement : measurements) {
00355     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00356     trajectory_builder->AddSensorData(
00357         kIMUSensorId.id,
00358         sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
00359                         Eigen::Vector3d::Zero()});
00360   }
00361   map_builder_->FinishTrajectory(trajectory_id);
00362   map_builder_->pose_graph()->RunFinalOptimization();
00363   int num_constraints = map_builder_->pose_graph()->constraints().size();
00364   int num_nodes =
00365       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00366           trajectory_id);
00367   EXPECT_GT(num_constraints, 0);
00368   EXPECT_GT(num_nodes, 0);
00369   // TODO(gaschler): Consider using in-memory to avoid side effects.
00370   const std::string filename = "temp-SaveLoadState.pbstream";
00371   io::ProtoStreamWriter writer(filename);
00372   map_builder_->SerializeState(/*include_unfinished_submaps=*/true, &writer);
00373   writer.Close();
00374 
00375   // Reset 'map_builder_'.
00376   BuildMapBuilder();
00377   io::ProtoStreamReader reader(filename);
00378   auto trajectory_remapping =
00379       map_builder_->LoadState(&reader, false /* load_frozen_state */);
00380   map_builder_->pose_graph()->RunFinalOptimization();
00381   EXPECT_EQ(num_constraints, map_builder_->pose_graph()->constraints().size());
00382   ASSERT_EQ(trajectory_remapping.size(), 1);
00383   int new_trajectory_id = trajectory_remapping.begin()->second;
00384   EXPECT_EQ(
00385       num_nodes,
00386       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00387           new_trajectory_id));
00388 }
00389 
00390 TEST_P(MapBuilderTestByGridType, LocalizationOnFrozenTrajectory2D) {
00391   if (GetParam() == GridType::TSDF) SetOptionsToTSDF2D();
00392   BuildMapBuilder();
00393   int temp_trajectory_id = CreateTrajectoryWithFakeData();
00394   map_builder_->pose_graph()->RunFinalOptimization();
00395   EXPECT_GT(map_builder_->pose_graph()->constraints().size(), 0);
00396   EXPECT_GT(
00397       map_builder_->pose_graph()->GetTrajectoryNodes().SizeOfTrajectoryOrZero(
00398           temp_trajectory_id),
00399       0);
00400   const std::string filename = "temp-LocalizationOnFrozenTrajectory2D.pbstream";
00401   io::ProtoStreamWriter writer(filename);
00402   map_builder_->SerializeState(/*include_unfinished_submaps=*/true, &writer);
00403   writer.Close();
00404 
00405   // Reset 'map_builder_'.
00406   local_slam_result_poses_.clear();
00407   SetOptionsEnableGlobalOptimization();
00408   BuildMapBuilder();
00409   io::ProtoStreamReader reader(filename);
00410   map_builder_->LoadState(&reader, true /* load_frozen_state */);
00411   map_builder_->pose_graph()->RunFinalOptimization();
00412   int trajectory_id = map_builder_->AddTrajectoryBuilder(
00413       {kRangeSensorId}, trajectory_builder_options_,
00414       GetLocalSlamResultCallback());
00415   TrajectoryBuilderInterface* trajectory_builder =
00416       map_builder_->GetTrajectoryBuilder(trajectory_id);
00417   transform::Rigid3d frozen_trajectory_to_global(
00418       Eigen::Vector3d(0.5, 0.4, 0),
00419       Eigen::Quaterniond(Eigen::AngleAxisd(1.2, Eigen::Vector3d::UnitZ())));
00420   Eigen::Vector3d travel_translation =
00421       Eigen::Vector3d(2., 1., 0.).normalized() * kTravelDistance;
00422   auto measurements = testing::GenerateFakeRangeMeasurements(
00423       travel_translation.cast<float>(), kDuration, kTimeStep,
00424       frozen_trajectory_to_global.cast<float>());
00425   for (auto& measurement : measurements) {
00426     measurement.time += common::FromSeconds(100.);
00427     trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
00428   }
00429   map_builder_->FinishTrajectory(trajectory_id);
00430   map_builder_->pose_graph()->RunFinalOptimization();
00431   EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
00432   EXPECT_NEAR(kTravelDistance,
00433               (local_slam_result_poses_.back().translation() -
00434                local_slam_result_poses_.front().translation())
00435                   .norm(),
00436               0.15 * kTravelDistance);
00437   EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 50);
00438   auto constraints = map_builder_->pose_graph()->constraints();
00439   int num_cross_trajectory_constraints = 0;
00440   for (const auto& constraint : constraints) {
00441     if (constraint.node_id.trajectory_id !=
00442         constraint.submap_id.trajectory_id) {
00443       ++num_cross_trajectory_constraints;
00444     }
00445   }
00446   EXPECT_GE(num_cross_trajectory_constraints, 3);
00447   // TODO(gaschler): Subscribe global slam callback, verify that all nodes are
00448   // optimized.
00449   EXPECT_THAT(constraints, ::testing::Contains(::testing::Field(
00450                                &PoseGraphInterface::Constraint::tag,
00451                                PoseGraphInterface::Constraint::INTER_SUBMAP)));
00452   const auto trajectory_nodes =
00453       map_builder_->pose_graph()->GetTrajectoryNodes();
00454   EXPECT_GE(trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 20);
00455   const auto submap_data = map_builder_->pose_graph()->GetAllSubmapData();
00456   EXPECT_GE(submap_data.SizeOfTrajectoryOrZero(trajectory_id), 5);
00457   const transform::Rigid3d global_pose =
00458       map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
00459       local_slam_result_poses_.back();
00460   EXPECT_NEAR(frozen_trajectory_to_global.translation().norm(),
00461               map_builder_->pose_graph()
00462                   ->GetLocalToGlobalTransform(trajectory_id)
00463                   .translation()
00464                   .norm(),
00465               0.1);
00466   const transform::Rigid3d expected_global_pose =
00467       frozen_trajectory_to_global *
00468       transform::Rigid3d::Translation(travel_translation);
00469   EXPECT_NEAR(
00470       0.,
00471       (global_pose.translation() - expected_global_pose.translation()).norm(),
00472       0.3)
00473       << "global_pose: " << global_pose
00474       << "expected_global_pose: " << expected_global_pose;
00475 }
00476 
00477 }  // namespace
00478 }  // namespace mapping
00479 }  // namespace cartographer


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