pose_graph_2d_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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/internal/2d/pose_graph_2d.h"
00018 
00019 #include <cmath>
00020 #include <memory>
00021 #include <random>
00022 
00023 #include "absl/memory/memory.h"
00024 #include "cartographer/common/lua_parameter_dictionary_test_helpers.h"
00025 #include "cartographer/common/thread_pool.h"
00026 #include "cartographer/common/time.h"
00027 #include "cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h"
00028 #include "cartographer/mapping/2d/submap_2d.h"
00029 #include "cartographer/transform/rigid_transform.h"
00030 #include "cartographer/transform/rigid_transform_test_helpers.h"
00031 #include "cartographer/transform/transform.h"
00032 #include "gmock/gmock.h"
00033 
00034 namespace cartographer {
00035 namespace mapping {
00036 namespace {
00037 
00038 class PoseGraph2DTest : public ::testing::Test {
00039  protected:
00040   PoseGraph2DTest() : thread_pool_(1) {
00041     // Builds a wavy, irregularly circular point cloud that is unique
00042     // rotationally. This gives us good rotational texture and avoids any
00043     // possibility of the CeresScanMatcher2D preferring free space (>
00044     // kMinProbability) to unknown space (== kMinProbability).
00045     for (float t = 0.f; t < 2.f * M_PI; t += 0.005f) {
00046       const float r = (std::sin(20.f * t) + 2.f) * std::sin(t + 2.f);
00047       point_cloud_.push_back(
00048           {Eigen::Vector3f{r * std::sin(t), r * std::cos(t), 0.f}});
00049     }
00050 
00051     {
00052       auto parameter_dictionary = common::MakeDictionary(R"text(
00053           return {
00054             num_range_data = 1,
00055             grid_options_2d = {
00056               grid_type = "PROBABILITY_GRID",
00057               resolution = 0.05,
00058             },
00059             range_data_inserter = {
00060               range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
00061               probability_grid_range_data_inserter = {
00062                 insert_free_space = true,
00063                 hit_probability = 0.53,
00064                 miss_probability = 0.495,
00065               },
00066             tsdf_range_data_inserter = {
00067               truncation_distance = 0.3,
00068               maximum_weight = 10.,
00069               update_free_space = false,
00070               normal_estimation_options = {
00071                 num_normal_samples = 4,
00072                 sample_radius = 0.5,
00073               },
00074               project_sdf_distance_to_scan_normal = false,
00075               update_weight_range_exponent = 0,
00076               update_weight_angle_scan_normal_to_ray_kernel_bandwidth = 0,
00077               update_weight_distance_cell_to_hit_kernel_bandwidth = 0,
00078             },
00079           },
00080         })text");
00081       active_submaps_ = absl::make_unique<ActiveSubmaps2D>(
00082           mapping::CreateSubmapsOptions2D(parameter_dictionary.get()));
00083     }
00084 
00085     {
00086       auto parameter_dictionary = common::MakeDictionary(R"text(
00087           return {
00088             optimize_every_n_nodes = 1000,
00089             constraint_builder = {
00090               sampling_ratio = 1.,
00091               max_constraint_distance = 6.,
00092               min_score = 0.5,
00093               global_localization_min_score = 0.6,
00094               loop_closure_translation_weight = 1.,
00095               loop_closure_rotation_weight = 1.,
00096               log_matches = true,
00097               fast_correlative_scan_matcher = {
00098                 linear_search_window = 3.,
00099                 angular_search_window = 0.1,
00100                 branch_and_bound_depth = 3,
00101               },
00102               ceres_scan_matcher = {
00103                 occupied_space_weight = 20.,
00104                 translation_weight = 10.,
00105                 rotation_weight = 1.,
00106                 ceres_solver_options = {
00107                   use_nonmonotonic_steps = true,
00108                   max_num_iterations = 50,
00109                   num_threads = 1,
00110                 },
00111               },
00112               fast_correlative_scan_matcher_3d = {
00113                 branch_and_bound_depth = 3,
00114                 full_resolution_depth = 3,
00115                 min_rotational_score = 0.1,
00116                 min_low_resolution_score = 0.5,
00117                 linear_xy_search_window = 4.,
00118                 linear_z_search_window = 4.,
00119                 angular_search_window = 0.1,
00120               },
00121               ceres_scan_matcher_3d = {
00122                 occupied_space_weight_0 = 20.,
00123                 translation_weight = 10.,
00124                 rotation_weight = 1.,
00125                 only_optimize_yaw = true,
00126                 ceres_solver_options = {
00127                   use_nonmonotonic_steps = true,
00128                   max_num_iterations = 50,
00129                   num_threads = 1,
00130                 },
00131               },
00132             },
00133             matcher_translation_weight = 1.,
00134             matcher_rotation_weight = 1.,
00135             optimization_problem = {
00136               acceleration_weight = 1.,
00137               rotation_weight = 1e2,
00138               huber_scale = 1.,
00139               local_slam_pose_translation_weight = 0.,
00140               local_slam_pose_rotation_weight = 0.,
00141               odometry_translation_weight = 0.,
00142               odometry_rotation_weight = 0.,
00143               fixed_frame_pose_translation_weight = 1e1,
00144               fixed_frame_pose_rotation_weight = 1e2,
00145               log_solver_summary = true,
00146               use_online_imu_extrinsics_in_3d = true,
00147               fix_z_in_3d = false,
00148               ceres_solver_options = {
00149                 use_nonmonotonic_steps = false,
00150                 max_num_iterations = 200,
00151                 num_threads = 1,
00152               },
00153             },
00154             max_num_final_iterations = 200,
00155             global_sampling_ratio = 0.01,
00156             log_residual_histograms = true,
00157             global_constraint_search_after_n_seconds = 10.0,
00158           })text");
00159       auto options = CreatePoseGraphOptions(parameter_dictionary.get());
00160       pose_graph_ = absl::make_unique<PoseGraph2D>(
00161           options,
00162           absl::make_unique<optimization::OptimizationProblem2D>(
00163               options.optimization_problem_options()),
00164           &thread_pool_);
00165     }
00166 
00167     current_pose_ = transform::Rigid2d::Identity();
00168   }
00169 
00170   void MoveRelativeWithNoise(const transform::Rigid2d& movement,
00171                              const transform::Rigid2d& noise) {
00172     current_pose_ = current_pose_ * movement;
00173     const sensor::PointCloud new_point_cloud = sensor::TransformPointCloud(
00174         point_cloud_,
00175         transform::Embed3D(current_pose_.inverse().cast<float>()));
00176     const sensor::RangeData range_data{
00177         Eigen::Vector3f::Zero(), new_point_cloud, {}};
00178     const transform::Rigid2d pose_estimate = noise * current_pose_;
00179     constexpr int kTrajectoryId = 0;
00180     active_submaps_->InsertRangeData(TransformRangeData(
00181         range_data, transform::Embed3D(pose_estimate.cast<float>())));
00182     std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
00183     for (const auto& submap : active_submaps_->submaps()) {
00184       insertion_submaps.push_back(submap);
00185     }
00186     pose_graph_->AddNode(
00187         std::make_shared<const TrajectoryNode::Data>(
00188             TrajectoryNode::Data{common::FromUniversal(0),
00189                                  Eigen::Quaterniond::Identity(),
00190                                  range_data.returns,
00191                                  {},
00192                                  {},
00193                                  {},
00194                                  transform::Embed3D(pose_estimate)}),
00195         kTrajectoryId, insertion_submaps);
00196   }
00197 
00198   void MoveRelative(const transform::Rigid2d& movement) {
00199     MoveRelativeWithNoise(movement, transform::Rigid2d::Identity());
00200   }
00201 
00202   template <typename Range>
00203   std::vector<int> ToVectorInt(const Range& range) {
00204     return std::vector<int>(range.begin(), range.end());
00205   }
00206 
00207   sensor::PointCloud point_cloud_;
00208   std::unique_ptr<ActiveSubmaps2D> active_submaps_;
00209   common::ThreadPool thread_pool_;
00210   std::unique_ptr<PoseGraph2D> pose_graph_;
00211   transform::Rigid2d current_pose_;
00212 };
00213 
00214 TEST_F(PoseGraph2DTest, EmptyMap) {
00215   pose_graph_->RunFinalOptimization();
00216   const auto nodes = pose_graph_->GetTrajectoryNodes();
00217   EXPECT_TRUE(nodes.empty());
00218 }
00219 
00220 TEST_F(PoseGraph2DTest, NoMovement) {
00221   MoveRelative(transform::Rigid2d::Identity());
00222   MoveRelative(transform::Rigid2d::Identity());
00223   MoveRelative(transform::Rigid2d::Identity());
00224   pose_graph_->RunFinalOptimization();
00225   const auto nodes = pose_graph_->GetTrajectoryNodes();
00226   ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
00227               ::testing::ContainerEq(std::vector<int>{0}));
00228   EXPECT_THAT(nodes.SizeOfTrajectoryOrZero(0), ::testing::Eq(3u));
00229   EXPECT_THAT(nodes.at(NodeId{0, 0}).global_pose,
00230               transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
00231   EXPECT_THAT(nodes.at(NodeId{0, 1}).global_pose,
00232               transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
00233   EXPECT_THAT(nodes.at(NodeId{0, 2}).global_pose,
00234               transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
00235 }
00236 
00237 TEST_F(PoseGraph2DTest, NoOverlappingNodes) {
00238   std::mt19937 rng(0);
00239   std::uniform_real_distribution<double> distribution(-1., 1.);
00240   std::vector<transform::Rigid2d> poses;
00241   for (int i = 0; i != 4; ++i) {
00242     MoveRelative(transform::Rigid2d({0.25 * distribution(rng), 5.}, 0.));
00243     poses.emplace_back(current_pose_);
00244   }
00245   pose_graph_->RunFinalOptimization();
00246   const auto nodes = pose_graph_->GetTrajectoryNodes();
00247   ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
00248               ::testing::ContainerEq(std::vector<int>{0}));
00249   for (int i = 0; i != 4; ++i) {
00250     EXPECT_THAT(
00251         poses[i],
00252         IsNearly(transform::Project2D(nodes.at(NodeId{0, i}).global_pose),
00253                  1e-2))
00254         << i;
00255   }
00256 }
00257 
00258 TEST_F(PoseGraph2DTest, ConsecutivelyOverlappingNodes) {
00259   std::mt19937 rng(0);
00260   std::uniform_real_distribution<double> distribution(-1., 1.);
00261   std::vector<transform::Rigid2d> poses;
00262   for (int i = 0; i != 5; ++i) {
00263     MoveRelative(transform::Rigid2d({0.25 * distribution(rng), 2.}, 0.));
00264     poses.emplace_back(current_pose_);
00265   }
00266   pose_graph_->RunFinalOptimization();
00267   const auto nodes = pose_graph_->GetTrajectoryNodes();
00268   ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
00269               ::testing::ContainerEq(std::vector<int>{0}));
00270   for (int i = 0; i != 5; ++i) {
00271     EXPECT_THAT(
00272         poses[i],
00273         IsNearly(transform::Project2D(nodes.at(NodeId{0, i}).global_pose),
00274                  1e-2))
00275         << i;
00276   }
00277 }
00278 
00279 TEST_F(PoseGraph2DTest, OverlappingNodes) {
00280   std::mt19937 rng(0);
00281   std::uniform_real_distribution<double> distribution(-1., 1.);
00282   std::vector<transform::Rigid2d> ground_truth;
00283   std::vector<transform::Rigid2d> poses;
00284   for (int i = 0; i != 5; ++i) {
00285     const double noise_x = 0.1 * distribution(rng);
00286     const double noise_y = 0.1 * distribution(rng);
00287     const double noise_orientation = 0.1 * distribution(rng);
00288     transform::Rigid2d noise({noise_x, noise_y}, noise_orientation);
00289     MoveRelativeWithNoise(
00290         transform::Rigid2d({0.15 * distribution(rng), 0.4}, 0.), noise);
00291     ground_truth.emplace_back(current_pose_);
00292     poses.emplace_back(noise * current_pose_);
00293   }
00294   pose_graph_->RunFinalOptimization();
00295   const auto nodes = pose_graph_->GetTrajectoryNodes();
00296   ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
00297               ::testing::ContainerEq(std::vector<int>{0}));
00298   transform::Rigid2d true_movement =
00299       ground_truth.front().inverse() * ground_truth.back();
00300   transform::Rigid2d movement_before = poses.front().inverse() * poses.back();
00301   transform::Rigid2d error_before = movement_before.inverse() * true_movement;
00302   transform::Rigid3d optimized_movement =
00303       nodes.BeginOfTrajectory(0)->data.global_pose.inverse() *
00304       std::prev(nodes.EndOfTrajectory(0))->data.global_pose;
00305   transform::Rigid2d optimized_error =
00306       transform::Project2D(optimized_movement).inverse() * true_movement;
00307   EXPECT_THAT(std::abs(optimized_error.normalized_angle()),
00308               ::testing::Lt(std::abs(error_before.normalized_angle())));
00309   EXPECT_THAT(optimized_error.translation().norm(),
00310               ::testing::Lt(error_before.translation().norm()));
00311 }
00312 
00313 }  // namespace
00314 }  // namespace mapping
00315 }  // namespace cartographer


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