test-mp2p_quality_voxels.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A Modular Optimization framework for Localization and mApping (MOLA)
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/core/exceptions.h>
17 #include <mrpt/core/get_env.h>
18 #include <mrpt/system/filesystem.h> // pathJoin()
19 
20 const bool VERBOSE = mrpt::get_env<bool>("VERBOSE", false);
21 const double SCALE = mrpt::get_env<double>("SCALE", 3.0);
22 
23 void unit_test()
24 {
25  const std::string datasetDir = mrpt::system::pathJoin({MOLA_TEST_DATASET_DIR, "loop_closures"});
26 
27  ASSERT_DIRECTORY_EXISTS_(datasetDir);
28 
29  const std::string datasetListFile = mrpt::system::pathJoin({datasetDir, "dataset.yaml"});
30 
31  const auto dataset = mrpt::containers::yaml::FromFile(datasetListFile);
32 
33  const auto badOnes = dataset["bad"];
34  const auto goodOnes = dataset["good"];
35 
36  ASSERT_(badOnes.isSequence());
37  ASSERT_(goodOnes.isSequence());
38 
40  mrpt::containers::yaml params;
41  params["voxel_layer_name"] = "localmap_voxels";
42  params["dist2quality_scale"] = SCALE;
43 
45  q.initialize(params);
46 
47  struct Entry
48  {
49  std::string global, local;
50  mrpt::poses::CPose3D local_pose_wrt_global;
51  bool is_good_lc;
52  };
53 
54  std::vector<Entry> LCs;
55 
56  auto lambdaProcessYaml = [&](const mrpt::containers::yaml::sequence_t& seq, bool are_good_lcs)
57  {
58  for (const auto& p : seq)
59  {
60  auto& lc = LCs.emplace_back();
61  lc.is_good_lc = are_good_lcs;
62  lc.global = p.asMap().at("global").as<std::string>();
63  lc.local = p.asMap().at("local").as<std::string>();
64  const auto v = p.asMap().at("final_pose").asSequence();
65  ASSERT_EQUAL_(v.size(), 6UL);
66  lc.local_pose_wrt_global = mrpt::poses::CPose3D::FromXYZYawPitchRoll(
67  v[0].as<double>(), v[1].as<double>(), v[2].as<double>(),
68  mrpt::DEG2RAD(v[3].as<double>()), mrpt::DEG2RAD(v[4].as<double>()),
69  mrpt::DEG2RAD(v[5].as<double>()));
70  }
71  };
72 
73  // Load GOOD loop-closures:
74  lambdaProcessYaml(goodOnes.asSequenceRange(), true);
75 
76  // Load BAD loop-closures:
77  lambdaProcessYaml(badOnes.asSequenceRange(), false);
78 
79  for (const auto& e : LCs)
80  {
82  pcG.load_from_file(mrpt::system::pathJoin({datasetDir, e.global}));
83 
85  pcL.load_from_file(mrpt::system::pathJoin({datasetDir, e.local}));
86 
87  const auto res = q.evaluate(pcG, pcL, e.local_pose_wrt_global, {});
88  const double quality = res.quality;
89 
90  if (VERBOSE)
91  {
92  std::cout << "- global: " << e.global << "\n"
93  << " local: " << e.local << "\n"
94  << " is_good: " << e.is_good_lc << "\n"
95  << " result_quality: " << quality << "\n";
96  }
97 
98  if ((quality < 0.2 && e.is_good_lc) || (quality >= 0.5 && !e.is_good_lc))
99  {
100  std::cerr << "Failed for test case:\n"
101  << " local : " << e.local << "\n"
102  << " global : " << e.global << "\n"
103  << " is_good : " << e.is_good_lc << "\n"
104  << " quality : " << quality << "\n";
105  throw std::runtime_error("test failed (see cerr above)");
106  }
107  }
108 }
109 
110 int main([[maybe_unused]] int argc, [[maybe_unused]] char** argv)
111 {
112  try
113  {
114  unit_test();
115  }
116  catch (std::exception& e)
117  {
118  std::cerr << mrpt::exception_to_str(e) << "\n";
119  return 1;
120  }
121 }
unit_test
void unit_test()
Definition: test-mp2p_quality_voxels.cpp:23
VERBOSE
const bool VERBOSE
Definition: test-mp2p_quality_voxels.cpp:20
test.res
res
Definition: test.py:11
mp2p_icp::QualityEvaluator_Voxels
Definition: QualityEvaluator_Voxels.h:22
QualityEvaluator_Voxels.h
Matching quality evaluator: comparison via voxel occupancy.
main
int main([[maybe_unused]] int argc, [[maybe_unused]] char **argv)
Definition: test-mp2p_quality_voxels.cpp:110
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:556
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
test.q
q
Definition: test.py:8
SCALE
const double SCALE
Definition: test-mp2p_quality_voxels.cpp:21


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:50