constraint_builder_3d_test.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 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 <functional>
20 
27 #include "gmock/gmock.h"
28 #include "gtest/gtest.h"
29 
30 namespace cartographer {
31 namespace mapping {
32 namespace constraints {
33 namespace {
34 
35 class MockCallback {
36  public:
37  MOCK_METHOD1(Run, void(const ConstraintBuilder3D::Result&));
38 };
39 
40 class ConstraintBuilder3DTest : public ::testing::Test {
41  protected:
42  void SetUp() override {
43  auto constraint_builder_parameters = test::ResolveLuaParameters(R"text(
44  include "pose_graph.lua"
45  POSE_GRAPH.constraint_builder.sampling_ratio = 1
46  POSE_GRAPH.constraint_builder.min_score = 0
47  POSE_GRAPH.constraint_builder.global_localization_min_score = 0
48  POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_low_resolution_score = 0
49  POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0
50  return POSE_GRAPH.constraint_builder)text");
51  constraint_builder_ = common::make_unique<ConstraintBuilder3D>(
52  CreateConstraintBuilderOptions(constraint_builder_parameters.get()),
53  &thread_pool_);
54  }
55 
56  std::unique_ptr<ConstraintBuilder3D> constraint_builder_;
57  MockCallback mock_;
58  common::testing::ThreadPoolForTesting thread_pool_;
59 };
60 
61 TEST_F(ConstraintBuilder3DTest, CallsBack) {
62  EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), 0);
63  EXPECT_CALL(mock_, Run(testing::IsEmpty()));
64  constraint_builder_->NotifyEndOfNode();
65  constraint_builder_->WhenDone(
66  std::bind(&MockCallback::Run, &mock_, std::placeholders::_1));
67  thread_pool_.WaitUntilIdle();
68  EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), 1);
69 }
70 
71 TEST_F(ConstraintBuilder3DTest, FindsConstraints) {
72  TrajectoryNode node;
73  auto node_data = std::make_shared<TrajectoryNode::Data>();
74  node_data->gravity_alignment = Eigen::Quaterniond::Identity();
75  node_data->high_resolution_point_cloud.push_back(
76  Eigen::Vector3f(0.1, 0.2, 0.3));
77  node_data->low_resolution_point_cloud.push_back(
78  Eigen::Vector3f(0.1, 0.2, 0.3));
79  node_data->rotational_scan_matcher_histogram = Eigen::VectorXf::Zero(3);
80  node_data->local_pose = transform::Rigid3d::Identity();
81  node.constant_data = node_data;
82  std::vector<TrajectoryNode> submap_nodes = {node};
83  SubmapId submap_id{0, 1};
84  Submap3D submap(0.1, 0.1, transform::Rigid3d::Identity());
85  int expected_nodes = 0;
86  for (int i = 0; i < 2; ++i) {
87  EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), expected_nodes);
88  for (int j = 0; j < 2; ++j) {
89  constraint_builder_->MaybeAddConstraint(
90  submap_id, &submap, NodeId{}, node.constant_data.get(), submap_nodes,
92  }
93  constraint_builder_->MaybeAddGlobalConstraint(
94  submap_id, &submap, NodeId{}, node.constant_data.get(), submap_nodes,
95  Eigen::Quaterniond::Identity(), Eigen::Quaterniond::Identity());
96  constraint_builder_->NotifyEndOfNode();
97  thread_pool_.WaitUntilIdle();
98  EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), ++expected_nodes);
99  constraint_builder_->NotifyEndOfNode();
100  thread_pool_.WaitUntilIdle();
101  EXPECT_EQ(constraint_builder_->GetNumFinishedNodes(), ++expected_nodes);
102  EXPECT_CALL(mock_,
103  Run(testing::AllOf(
104  testing::SizeIs(3),
105  testing::Each(testing::Field(
108  constraint_builder_->WhenDone(
109  std::bind(&MockCallback::Run, &mock_, std::placeholders::_1));
110  thread_pool_.WaitUntilIdle();
111  constraint_builder_->DeleteScanMatcher(submap_id);
112  }
113 }
114 
115 } // namespace
116 } // namespace constraints
117 } // namespace mapping
118 } // namespace cartographer
MockCallback mock_
enum cartographer::mapping::PoseGraphInterface::Constraint::Tag tag
std::unique_ptr< ConstraintBuilder3D > constraint_builder_
proto::ConstraintBuilderOptions CreateConstraintBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
void Run(const std::string &configuration_directory, const std::string &configuration_basename)
std::unique_ptr<::cartographer::common::LuaParameterDictionary > ResolveLuaParameters(const std::string &lua_code)
common::testing::ThreadPoolForTesting thread_pool_


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