pose_graph_2d_test.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 <cmath>
20 #include <memory>
21 #include <random>
22 
32 #include "gmock/gmock.h"
33 
34 namespace cartographer {
35 namespace mapping {
36 namespace {
37 
38 class PoseGraph2DTest : public ::testing::Test {
39  protected:
40  PoseGraph2DTest() : thread_pool_(1) {
41  // Builds a wavy, irregularly circular point cloud that is unique
42  // rotationally. This gives us good rotational texture and avoids any
43  // possibility of the CeresScanMatcher2D preferring free space (>
44  // kMinProbability) to unknown space (== kMinProbability).
45  for (float t = 0.f; t < 2.f * M_PI; t += 0.005f) {
46  const float r = (std::sin(20.f * t) + 2.f) * std::sin(t + 2.f);
47  point_cloud_.emplace_back(r * std::sin(t), r * std::cos(t), 0.f);
48  }
49 
50  {
51  auto parameter_dictionary = common::MakeDictionary(R"text(
52  return {
53  num_range_data = 1,
54  grid_options_2d = {
55  grid_type = "PROBABILITY_GRID",
56  resolution = 0.05,
57  },
58  range_data_inserter = {
59  range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
60  probability_grid_range_data_inserter = {
61  insert_free_space = true,
62  hit_probability = 0.53,
63  miss_probability = 0.495,
64  },
65  },
66  })text");
67  active_submaps_ = common::make_unique<ActiveSubmaps2D>(
68  mapping::CreateSubmapsOptions2D(parameter_dictionary.get()));
69  }
70 
71  {
72  auto parameter_dictionary = common::MakeDictionary(R"text(
73  return {
74  optimize_every_n_nodes = 1000,
75  constraint_builder = {
76  sampling_ratio = 1.,
77  max_constraint_distance = 6.,
78  min_score = 0.5,
79  global_localization_min_score = 0.6,
80  loop_closure_translation_weight = 1.,
81  loop_closure_rotation_weight = 1.,
82  log_matches = true,
83  fast_correlative_scan_matcher = {
84  linear_search_window = 3.,
85  angular_search_window = 0.1,
86  branch_and_bound_depth = 3,
87  },
88  ceres_scan_matcher = {
89  occupied_space_weight = 20.,
90  translation_weight = 10.,
91  rotation_weight = 1.,
92  ceres_solver_options = {
93  use_nonmonotonic_steps = true,
94  max_num_iterations = 50,
95  num_threads = 1,
96  },
97  },
98  fast_correlative_scan_matcher_3d = {
99  branch_and_bound_depth = 3,
100  full_resolution_depth = 3,
101  min_rotational_score = 0.1,
102  min_low_resolution_score = 0.5,
103  linear_xy_search_window = 4.,
104  linear_z_search_window = 4.,
105  angular_search_window = 0.1,
106  },
107  ceres_scan_matcher_3d = {
108  occupied_space_weight_0 = 20.,
109  translation_weight = 10.,
110  rotation_weight = 1.,
111  only_optimize_yaw = true,
112  ceres_solver_options = {
113  use_nonmonotonic_steps = true,
114  max_num_iterations = 50,
115  num_threads = 1,
116  },
117  },
118  },
119  matcher_translation_weight = 1.,
120  matcher_rotation_weight = 1.,
121  optimization_problem = {
122  acceleration_weight = 1.,
123  rotation_weight = 1e2,
124  huber_scale = 1.,
125  local_slam_pose_translation_weight = 0.,
126  local_slam_pose_rotation_weight = 0.,
127  odometry_translation_weight = 0.,
128  odometry_rotation_weight = 0.,
129  fixed_frame_pose_translation_weight = 1e1,
130  fixed_frame_pose_rotation_weight = 1e2,
131  log_solver_summary = true,
132  ceres_solver_options = {
133  use_nonmonotonic_steps = false,
134  max_num_iterations = 200,
135  num_threads = 1,
136  },
137  },
138  max_num_final_iterations = 200,
139  global_sampling_ratio = 0.01,
140  log_residual_histograms = true,
141  global_constraint_search_after_n_seconds = 10.0,
142  })text");
143  auto options = CreatePoseGraphOptions(parameter_dictionary.get());
144  pose_graph_ = common::make_unique<PoseGraph2D>(
145  options,
146  common::make_unique<optimization::OptimizationProblem2D>(
147  options.optimization_problem_options()),
148  &thread_pool_);
149  }
150 
152  }
153 
154  void MoveRelativeWithNoise(const transform::Rigid2d& movement,
155  const transform::Rigid2d& noise) {
156  current_pose_ = current_pose_ * movement;
157  const sensor::PointCloud new_point_cloud = sensor::TransformPointCloud(
158  point_cloud_,
159  transform::Embed3D(current_pose_.inverse().cast<float>()));
160  std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
161  for (const auto& submap : active_submaps_->submaps()) {
162  insertion_submaps.push_back(submap);
163  }
164  const sensor::RangeData range_data{
165  Eigen::Vector3f::Zero(), new_point_cloud, {}};
166  const transform::Rigid2d pose_estimate = noise * current_pose_;
167  constexpr int kTrajectoryId = 0;
168  active_submaps_->InsertRangeData(TransformRangeData(
169  range_data, transform::Embed3D(pose_estimate.cast<float>())));
170 
171  pose_graph_->AddNode(
172  std::make_shared<const TrajectoryNode::Data>(
173  TrajectoryNode::Data{common::FromUniversal(0),
174  Eigen::Quaterniond::Identity(),
175  range_data.returns,
176  {},
177  {},
178  {},
179  transform::Embed3D(pose_estimate)}),
180  kTrajectoryId, insertion_submaps);
181  }
182 
183  void MoveRelative(const transform::Rigid2d& movement) {
184  MoveRelativeWithNoise(movement, transform::Rigid2d::Identity());
185  }
186 
187  template <typename Range>
188  std::vector<int> ToVectorInt(const Range& range) {
189  return std::vector<int>(range.begin(), range.end());
190  }
191 
193  std::unique_ptr<ActiveSubmaps2D> active_submaps_;
194  common::ThreadPool thread_pool_;
195  std::unique_ptr<PoseGraph2D> pose_graph_;
197 };
198 
199 TEST_F(PoseGraph2DTest, EmptyMap) {
200  pose_graph_->RunFinalOptimization();
201  const auto nodes = pose_graph_->GetTrajectoryNodes();
202  EXPECT_TRUE(nodes.empty());
203 }
204 
205 TEST_F(PoseGraph2DTest, NoMovement) {
206  MoveRelative(transform::Rigid2d::Identity());
207  MoveRelative(transform::Rigid2d::Identity());
208  MoveRelative(transform::Rigid2d::Identity());
209  pose_graph_->RunFinalOptimization();
210  const auto nodes = pose_graph_->GetTrajectoryNodes();
211  ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
212  ::testing::ContainerEq(std::vector<int>{0}));
213  EXPECT_THAT(nodes.SizeOfTrajectoryOrZero(0), ::testing::Eq(3u));
214  EXPECT_THAT(nodes.at(NodeId{0, 0}).global_pose,
215  transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
216  EXPECT_THAT(nodes.at(NodeId{0, 1}).global_pose,
217  transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
218  EXPECT_THAT(nodes.at(NodeId{0, 2}).global_pose,
219  transform::IsNearly(transform::Rigid3d::Identity(), 1e-2));
220 }
221 
222 TEST_F(PoseGraph2DTest, NoOverlappingNodes) {
223  std::mt19937 rng(0);
224  std::uniform_real_distribution<double> distribution(-1., 1.);
225  std::vector<transform::Rigid2d> poses;
226  for (int i = 0; i != 4; ++i) {
227  MoveRelative(transform::Rigid2d({0.25 * distribution(rng), 5.}, 0.));
228  poses.emplace_back(current_pose_);
229  }
230  pose_graph_->RunFinalOptimization();
231  const auto nodes = pose_graph_->GetTrajectoryNodes();
232  ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
233  ::testing::ContainerEq(std::vector<int>{0}));
234  for (int i = 0; i != 4; ++i) {
235  EXPECT_THAT(
236  poses[i],
237  IsNearly(transform::Project2D(nodes.at(NodeId{0, i}).global_pose),
238  1e-2))
239  << i;
240  }
241 }
242 
243 TEST_F(PoseGraph2DTest, ConsecutivelyOverlappingNodes) {
244  std::mt19937 rng(0);
245  std::uniform_real_distribution<double> distribution(-1., 1.);
246  std::vector<transform::Rigid2d> poses;
247  for (int i = 0; i != 5; ++i) {
248  MoveRelative(transform::Rigid2d({0.25 * distribution(rng), 2.}, 0.));
249  poses.emplace_back(current_pose_);
250  }
251  pose_graph_->RunFinalOptimization();
252  const auto nodes = pose_graph_->GetTrajectoryNodes();
253  ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
254  ::testing::ContainerEq(std::vector<int>{0}));
255  for (int i = 0; i != 5; ++i) {
256  EXPECT_THAT(
257  poses[i],
258  IsNearly(transform::Project2D(nodes.at(NodeId{0, i}).global_pose),
259  1e-2))
260  << i;
261  }
262 }
263 
264 TEST_F(PoseGraph2DTest, OverlappingNodes) {
265  std::mt19937 rng(0);
266  std::uniform_real_distribution<double> distribution(-1., 1.);
267  std::vector<transform::Rigid2d> ground_truth;
268  std::vector<transform::Rigid2d> poses;
269  for (int i = 0; i != 5; ++i) {
270  const double noise_x = 0.1 * distribution(rng);
271  const double noise_y = 0.1 * distribution(rng);
272  const double noise_orientation = 0.1 * distribution(rng);
273  transform::Rigid2d noise({noise_x, noise_y}, noise_orientation);
274  MoveRelativeWithNoise(
275  transform::Rigid2d({0.15 * distribution(rng), 0.4}, 0.), noise);
276  ground_truth.emplace_back(current_pose_);
277  poses.emplace_back(noise * current_pose_);
278  }
279  pose_graph_->RunFinalOptimization();
280  const auto nodes = pose_graph_->GetTrajectoryNodes();
281  ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
282  ::testing::ContainerEq(std::vector<int>{0}));
283  transform::Rigid2d true_movement =
284  ground_truth.front().inverse() * ground_truth.back();
285  transform::Rigid2d movement_before = poses.front().inverse() * poses.back();
286  transform::Rigid2d error_before = movement_before.inverse() * true_movement;
287  transform::Rigid3d optimized_movement =
288  nodes.BeginOfTrajectory(0)->data.global_pose.inverse() *
289  std::prev(nodes.EndOfTrajectory(0))->data.global_pose;
290  transform::Rigid2d optimized_error =
291  transform::Project2D(optimized_movement).inverse() * true_movement;
292  EXPECT_THAT(std::abs(optimized_error.normalized_angle()),
293  ::testing::Lt(std::abs(error_before.normalized_angle())));
294  EXPECT_THAT(optimized_error.translation().norm(),
295  ::testing::Lt(error_before.translation().norm()));
296 }
297 
298 } // namespace
299 } // namespace mapping
300 } // namespace cartographer
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
Definition: point_cloud.cc:25
transform::Rigid2d current_pose_
Rigid3< double > Rigid3d
sensor::PointCloud point_cloud_
proto::SubmapsOptions2D CreateSubmapsOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
Definition: submap_2d.cc:35
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
std::unique_ptr< ActiveSubmaps2D > active_submaps_
Rigid3< T > Embed3D(const Rigid2< T > &transform)
Definition: transform.h:110
RangeData TransformRangeData(const RangeData &range_data, const transform::Rigid3f &transform)
Definition: range_data.cc:25
Rigid2< T > Project2D(const Rigid3< T > &transform)
Definition: transform.h:103
static Rigid2< FloatType > Identity()
Rigid2< double > Rigid2d
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
proto::PoseGraphOptions CreatePoseGraphOptions(common::LuaParameterDictionary *const parameter_dictionary)
Definition: pose_graph.cc:72
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
std::unique_ptr< PoseGraph2D > pose_graph_
common::ThreadPool thread_pool_


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