optimization_problem_3d_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 <random>
20 
21 #include "Eigen/Core"
26 #include "glog/logging.h"
27 #include "gmock/gmock.h"
28 
29 namespace cartographer {
30 namespace mapping {
31 namespace optimization {
32 namespace {
33 
34 class OptimizationProblem3DTest : public ::testing::Test {
35  protected:
36  OptimizationProblem3DTest()
37  : optimization_problem_(CreateOptions()), rng_(45387) {}
38 
39  optimization::proto::OptimizationProblemOptions CreateOptions() {
40  auto parameter_dictionary = common::MakeDictionary(R"text(
41  return {
42  acceleration_weight = 1e-4,
43  rotation_weight = 1e-2,
44  huber_scale = 1.,
45  local_slam_pose_translation_weight = 1e-2,
46  local_slam_pose_rotation_weight = 1e-2,
47  odometry_translation_weight = 1e-2,
48  odometry_rotation_weight = 1e-2,
49  fixed_frame_pose_translation_weight = 1e1,
50  fixed_frame_pose_rotation_weight = 1e2,
51  log_solver_summary = true,
52  ceres_solver_options = {
53  use_nonmonotonic_steps = false,
54  max_num_iterations = 200,
55  num_threads = 4,
56  },
57  })text");
59  parameter_dictionary.get());
60  }
61 
62  transform::Rigid3d RandomTransform(double translation_size,
63  double rotation_size) {
64  std::uniform_real_distribution<double> translation_distribution(
65  -translation_size, translation_size);
66  const double x = translation_distribution(rng_);
67  const double y = translation_distribution(rng_);
68  const double z = translation_distribution(rng_);
69  std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
70  rotation_size);
71  const double rx = rotation_distribution(rng_);
72  const double ry = rotation_distribution(rng_);
73  const double rz = rotation_distribution(rng_);
74  return transform::Rigid3d(Eigen::Vector3d(x, y, z),
76  Eigen::Vector3d(rx, ry, rz)));
77  }
78 
79  transform::Rigid3d RandomYawOnlyTransform(double translation_size,
80  double rotation_size) {
81  std::uniform_real_distribution<double> translation_distribution(
82  -translation_size, translation_size);
83  const double x = translation_distribution(rng_);
84  const double y = translation_distribution(rng_);
85  const double z = translation_distribution(rng_);
86  std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
87  rotation_size);
88  const double rz = rotation_distribution(rng_);
89  return transform::Rigid3d(Eigen::Vector3d(x, y, z),
91  Eigen::Vector3d(0., 0., rz)));
92  }
93 
94  OptimizationProblem3D optimization_problem_;
95  std::mt19937 rng_;
96 };
97 
98 transform::Rigid3d AddNoise(const transform::Rigid3d& transform,
99  const transform::Rigid3d& noise) {
100  const Eigen::Quaterniond noisy_rotation(noise.rotation() *
101  transform.rotation());
102  return transform::Rigid3d(transform.translation() + noise.translation(),
103  noisy_rotation);
104 }
105 
106 TEST_F(OptimizationProblem3DTest, ReducesNoise) {
107  constexpr int kNumNodes = 100;
108  const transform::Rigid3d kSubmap0Transform = transform::Rigid3d::Identity();
109  const transform::Rigid3d kSubmap2Transform = transform::Rigid3d::Rotation(
110  Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitZ()));
111  const int kTrajectoryId = 0;
112 
113  struct NoisyNode {
114  transform::Rigid3d ground_truth_pose;
115  transform::Rigid3d noise;
116  };
117  std::vector<NoisyNode> test_data;
118  for (int j = 0; j != kNumNodes; ++j) {
119  test_data.push_back(
120  NoisyNode{RandomTransform(10., 3.), RandomYawOnlyTransform(0.2, 0.3)});
121  }
122 
124  for (const NoisyNode& node : test_data) {
125  const transform::Rigid3d pose =
126  AddNoise(node.ground_truth_pose, node.noise);
127  optimization_problem_.AddImuData(
128  kTrajectoryId, sensor::ImuData{now, Eigen::Vector3d::UnitZ() * 9.81,
129  Eigen::Vector3d::Zero()});
130  optimization_problem_.AddTrajectoryNode(kTrajectoryId,
131  NodeSpec3D{now, pose, pose});
132  now += common::FromSeconds(0.01);
133  }
134 
135  std::vector<OptimizationProblem3D::Constraint> constraints;
136  for (int j = 0; j != kNumNodes; ++j) {
137  constraints.push_back(OptimizationProblem3D::Constraint{
138  SubmapId{kTrajectoryId, 0}, NodeId{kTrajectoryId, j},
139  OptimizationProblem3D::Constraint::Pose{
140  AddNoise(test_data[j].ground_truth_pose, test_data[j].noise), 1.,
141  1.}});
142  // We add an additional independent, but equally noisy observation.
143  constraints.push_back(OptimizationProblem3D::Constraint{
144  SubmapId{kTrajectoryId, 1}, NodeId{kTrajectoryId, j},
145  OptimizationProblem3D::Constraint::Pose{
146  AddNoise(test_data[j].ground_truth_pose,
147  RandomYawOnlyTransform(0.2, 0.3)),
148  1., 1.}});
149  // We add very noisy data with a low weight to verify it is mostly ignored.
150  constraints.push_back(OptimizationProblem3D::Constraint{
151  SubmapId{kTrajectoryId, 2}, NodeId{kTrajectoryId, j},
152  OptimizationProblem3D::Constraint::Pose{
153  kSubmap2Transform.inverse() * test_data[j].ground_truth_pose *
154  RandomTransform(1e3, 3.),
155  1e-9, 1e-9}});
156  }
157 
158  double translation_error_before = 0.;
159  double rotation_error_before = 0.;
160  const auto& node_data = optimization_problem_.node_data();
161  for (int j = 0; j != kNumNodes; ++j) {
162  translation_error_before +=
163  (test_data[j].ground_truth_pose.translation() -
164  node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
165  .norm();
166  rotation_error_before +=
167  transform::GetAngle(test_data[j].ground_truth_pose.inverse() *
168  node_data.at(NodeId{kTrajectoryId, j}).global_pose);
169  }
170 
171  optimization_problem_.AddSubmap(kTrajectoryId, kSubmap0Transform);
172  optimization_problem_.AddSubmap(kTrajectoryId, kSubmap0Transform);
173  optimization_problem_.AddSubmap(kTrajectoryId, kSubmap2Transform);
174  const std::set<int> kFrozen = {};
175  optimization_problem_.Solve(constraints, kFrozen, {});
176 
177  double translation_error_after = 0.;
178  double rotation_error_after = 0.;
179  for (int j = 0; j != kNumNodes; ++j) {
180  translation_error_after +=
181  (test_data[j].ground_truth_pose.translation() -
182  node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
183  .norm();
184  rotation_error_after +=
185  transform::GetAngle(test_data[j].ground_truth_pose.inverse() *
186  node_data.at(NodeId{kTrajectoryId, j}).global_pose);
187  }
188 
189  EXPECT_GT(0.8 * translation_error_before, translation_error_after);
190  EXPECT_GT(0.8 * rotation_error_before, rotation_error_after);
191 }
192 
193 } // namespace
194 } // namespace optimization
195 } // namespace mapping
196 } // namespace cartographer
Eigen::Quaternion< T > AngleAxisVectorToRotationQuaternion(const Eigen::Matrix< T, 3, 1 > &angle_axis)
Definition: transform.h:86
std::mt19937 rng_
static Rigid3 Rotation(const AngleAxis &angle_axis)
Rigid3< double > Rigid3d
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
proto::OptimizationProblemOptions CreateOptimizationProblemOptions(common::LuaParameterDictionary *const parameter_dictionary)
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
Duration FromSeconds(const double seconds)
Definition: time.cc:24
OptimizationProblem3D optimization_problem_
FloatType GetAngle(const Rigid3< FloatType > &transform)
Definition: transform.h:34
transform::Rigid3d pose


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