Generator.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
16 #include <mrpt/config/CConfigFile.h>
17 #include <mrpt/config/CConfigFileMemory.h>
18 #include <mrpt/containers/yaml.h>
19 #include <mrpt/core/get_env.h>
20 #include <mrpt/maps/CMultiMetricMap.h>
21 #include <mrpt/maps/CPointsMapXYZIRT.h>
22 #include <mrpt/maps/CSimplePointsMap.h>
23 #include <mrpt/obs/CObservation2DRangeScan.h>
24 #include <mrpt/obs/CObservation3DRangeScan.h>
25 #include <mrpt/obs/CObservationPointCloud.h>
26 #include <mrpt/obs/CObservationRotatingScan.h>
27 #include <mrpt/obs/CObservationVelodyneScan.h>
28 #include <mrpt/obs/CSensoryFrame.h>
29 #include <mrpt/system/filesystem.h>
30 
31 #include <filesystem>
32 namespace fs = std::filesystem;
33 
34 #if defined(__unix__)
35 #include <dlfcn.h>
36 #endif
37 
39 
40 using namespace mp2p_icp_filters;
41 
42 Generator::Generator() : mrpt::system::COutputLogger("Generator") {}
43 
45  const mrpt::containers::yaml& c, Generator& parent)
46 {
47  using namespace std::string_literals;
48 
49  MCP_LOAD_OPT(c, target_layer);
50  MCP_LOAD_OPT(c, metric_map_definition_ini_file);
51  MCP_LOAD_OPT(c, process_class_names_regex);
52  MCP_LOAD_OPT(c, process_sensor_labels_regex);
53  MCP_LOAD_OPT(c, throw_on_unhandled_observation_class);
54 
55  if (c.has("metric_map_definition"))
56  {
57  // Store values here:
58  auto& trg = metric_map_definition;
59 
60  const std::set<std::string> allowedTopKeys = {"class", "plugin"};
61 
62  ASSERT_(c["metric_map_definition"].isMap());
63  const auto mmd = c["metric_map_definition"].asMap();
64  for (const auto& [k, v] : mmd)
65  {
66  const auto key = k.as<std::string>();
67  if (v.isNullNode()) continue; // ignore
68  if (v.isScalar())
69  {
70  if (allowedTopKeys.count(key) != 0)
71  {
72  // simple key=value:
73  ASSERT_(v.isScalar());
74  trg[key] = v.as<std::string>();
75  continue;
76  }
77  else
78  {
79  THROW_EXCEPTION_FMT(
80  "scalar key '%s' not allowed here.", key.c_str());
81  }
82  }
83  // if should then be a map
84  if (!v.isMap())
85  THROW_EXCEPTION_FMT(
86  "key '%s' must be either a scalar or a map", key.c_str());
87 
88  trg[key] = mrpt::containers::yaml::Map();
89  auto& newMap = trg.asMap().at(key).asMap();
90 
91  for (const auto& [kk, vv] : v.asMap())
92  {
93  const std::string val = vv.as<std::string>();
94  // Special case: handle parameterizable formulas:
95  if (val.substr(0, 3) == "$f{"s)
96  {
97  ASSERTMSG_(
98  val.back() == '}', "Missing '}' in '$f{' formula");
99 
100  const auto ks = kk.as<std::string>();
101 
102  auto [it, exist] = newMap.insert({ks, .0});
103  double& placeholder =
104  *std::any_cast<double>(&it->second.asScalar());
105 
107  val.substr(3, val.size() - 4), placeholder);
108  }
109  else
110  {
111  // regular entry:
112  newMap[kk.as<std::string>()] = val;
113  }
114  }
115  }
116 
117  std::stringstream ss;
118  ss << "Using this metric_map_definition:\n"s << metric_map_definition;
119  parent.logStr(mrpt::system::LVL_DEBUG, ss.str());
120  }
121 }
122 
123 void Generator::initialize(const mrpt::containers::yaml& c)
124 {
125  MRPT_START
126 
127  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
128  params_.load_from_yaml(c, *this);
129 
133 
134  initialized_ = true;
135  MRPT_END
136 }
137 
139  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
140  const std::optional<mrpt::poses::CPose3D>& robotPose) const
141 {
142  MRPT_START
143 
144  Parameterizable::checkAllParametersAreRealized();
145 
146  ASSERTMSG_(
147  initialized_,
148  "initialize() must be called once before using process().");
149 
150  const auto obsClassName = o.GetRuntimeClass()->className;
151 
152  MRPT_LOG_DEBUG_FMT(
153  "Processing observation type='%s' label='%s'", obsClassName,
154  o.sensorLabel.c_str());
155 
156  // default: use point clouds:
159  {
160  return implProcessDefault(o, out, robotPose);
161  }
162  else
163  { //
164  return implProcessCustomMap(o, out, robotPose);
165  }
166 
167  MRPT_END
168 }
169 
171  [[maybe_unused]] const mrpt::obs::CObservation2DRangeScan& pc,
172  [[maybe_unused]] mp2p_icp::metric_map_t& out,
173  [[maybe_unused]] const std::optional<mrpt::poses::CPose3D>& robotPose) const
174 {
175  return false; // Not implemented
176 }
177 
179  const mrpt::obs::CObservationVelodyneScan& pc, mp2p_icp::metric_map_t& out,
180  const std::optional<mrpt::poses::CPose3D>& robotPose) const
181 {
182  mrpt::maps::CPointsMap::Ptr outPc = GetOrCreatePointLayer(
183  out, params_.target_layer, false /*does not allow empty name*/,
184  "mrpt::maps::CPointsMapXYZIRT" /* creation class if not existing */);
185  ASSERT_(outPc);
186 
187  auto m = std::dynamic_pointer_cast<mrpt::maps::CPointsMapXYZIRT>(outPc);
188  ASSERTMSG_(
189  m,
190  "Output layer must be of type mrpt::maps::CPointsMapXYZIRT for the "
191  "specialized filterVelodyneScan() generator.");
192 
193  m->insertObservation(pc, robotPose);
194 
195  return true; // implemented
196 }
197 
199  [[maybe_unused]] const mrpt::obs::CObservation3DRangeScan& pc,
200  [[maybe_unused]] mp2p_icp::metric_map_t& out,
201  [[maybe_unused]] const std::optional<mrpt::poses::CPose3D>& robotPose) const
202 {
203  return false; // Not implemented
204 }
205 
207  const mrpt::maps::CPointsMap& pc, const mrpt::poses::CPose3D& sensorPose,
209  const std::optional<mrpt::poses::CPose3D>& robotPose) const
210 {
211  // Create if new: Append to existing layer, if already existed.
212  mrpt::maps::CPointsMap::Ptr outPc;
213  if (auto itLy = out.layers.find(params_.target_layer);
214  itLy != out.layers.end())
215  {
216  outPc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itLy->second);
217  if (!outPc)
218  THROW_EXCEPTION_FMT(
219  "Layer '%s' must be of point cloud type.",
220  params_.target_layer.c_str());
221  }
222  else
223  {
224  // Make a new layer of the same type than the input cloud:
225  outPc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(
226  pc.GetRuntimeClass()->ptrCreateObject());
227  ASSERT_(outPc);
228 
229  MRPT_LOG_DEBUG_FMT(
230  "[filterPointCloud] Created new layer '%s' of type '%s'",
231  params_.target_layer.c_str(), outPc->GetRuntimeClass()->className);
232 
233  out.layers[params_.target_layer] = outPc;
234  }
235 
236  const mrpt::poses::CPose3D p =
237  robotPose ? robotPose.value() + sensorPose : sensorPose;
238 
239  outPc->insertAnotherMap(&pc, p);
240 
241  const bool sanityPassed = mp2p_icp::pointcloud_sanity_check(*outPc);
242  ASSERT_(sanityPassed);
243 
244  return true;
245 }
246 
248  [[maybe_unused]] const mrpt::obs::CObservationRotatingScan& pc,
249  [[maybe_unused]] mp2p_icp::metric_map_t& out,
250  [[maybe_unused]] const std::optional<mrpt::poses::CPose3D>& robotPose) const
251 {
252  return false; // Not implemented
253 }
254 
256  const GeneratorSet& generators, const mrpt::obs::CObservation& obs,
257  mp2p_icp::metric_map_t& output,
258  const std::optional<mrpt::poses::CPose3D>& robotPose)
259 {
260  ASSERT_(!generators.empty());
261  bool anyHandled = false;
262  for (const auto& g : generators)
263  {
264  ASSERT_(g.get() != nullptr);
265  bool handled = g->process(obs, output, robotPose);
266  anyHandled = anyHandled || handled;
267  }
268  return anyHandled;
269 }
270 
272  const GeneratorSet& generators, const mrpt::obs::CObservation& obs,
273  const std::optional<mrpt::poses::CPose3D>& robotPose)
274 {
276  apply_generators(generators, obs, pc, robotPose);
277  return pc;
278 }
279 
281  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf,
282  const std::optional<mrpt::poses::CPose3D>& robotPose)
283 {
285  apply_generators(generators, sf, pc, robotPose);
286  return pc;
287 }
288 
290  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf,
291  mp2p_icp::metric_map_t& output,
292  const std::optional<mrpt::poses::CPose3D>& robotPose)
293 {
294  ASSERT_(!generators.empty());
295  bool anyHandled = false;
296  for (const auto& g : generators)
297  {
298  ASSERT_(g.get() != nullptr);
299  for (const auto& obs : sf)
300  {
301  if (!obs) continue;
302  const bool handled = g->process(*obs, output, robotPose);
303 
304  anyHandled = anyHandled || handled;
305  }
306  }
307  return anyHandled;
308 }
309 
311  const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel)
312 {
313  if (c.isNullNode()) return {};
314 
315  ASSERT_(c.isSequence());
316 
318 
319  for (const auto& entry : c.asSequence())
320  {
321  const auto& e = entry.asMap();
322 
323  const auto sClass = e.at("class_name").as<std::string>();
324  auto o = mrpt::rtti::classFactory(sClass);
325  ASSERT_(o);
326 
327  auto f = std::dynamic_pointer_cast<Generator>(o);
328  ASSERTMSG_(
329  f, mrpt::format(
330  "`%s` class seems not to be derived from Generator",
331  sClass.c_str()));
332 
333  f->setMinLoggingLevel(vLevel);
334 
335  f->initialize(e.at("params"));
336  generators.push_back(f);
337  }
338 
339  return generators;
340 }
341 
343  const std::string& filename, const mrpt::system::VerbosityLevel& vLevel)
344 {
345  const auto yamlContent = mrpt::containers::yaml::FromFile(filename);
346 
347  ASSERT_(
348  yamlContent.has("generators") &&
349  yamlContent["generators"].isSequence());
350 
351  return generators_from_yaml(yamlContent["generators"], vLevel);
352 }
353 
355  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
356  const std::optional<mrpt::poses::CPose3D>& robotPose) const
357 {
358  using namespace mrpt::obs;
359  using namespace std::string_literals;
360 
361  bool processed = false;
362 
363  const auto obsClassName = o.GetRuntimeClass()->className;
364 
365  // user-given filters: Done *AFTER* creating the map, if needed.
366  if (obsClassName == "mrpt::obs::CObservationComment"s ||
367  obsClassName == "mrpt::obs::CObservationGPS"s ||
368  obsClassName == "mrpt::obs::CObservationRobotPose"s ||
369  !std::regex_match(obsClassName, process_class_names_regex_) ||
370  !std::regex_match(o.sensorLabel, process_sensor_labels_regex_))
371  {
372  MRPT_LOG_DEBUG_STREAM("Skipping this observation");
373  return false;
374  }
375 
376  // load lazy-load from disk:
377  o.load();
378 
379  if (auto oRS = dynamic_cast<const CObservationRotatingScan*>(&o); oRS)
380  processed = filterRotatingScan(*oRS, out, robotPose);
381  else if (auto o0 = dynamic_cast<const CObservationPointCloud*>(&o); o0)
382  {
383  ASSERT_(o0->pointcloud);
384  processed =
385  filterPointCloud(*o0->pointcloud, o0->sensorPose, out, robotPose);
386  }
387  else if (auto o1 = dynamic_cast<const CObservation2DRangeScan*>(&o); o1)
388  processed = filterScan2D(*o1, out, robotPose);
389  else if (auto o2 = dynamic_cast<const CObservation3DRangeScan*>(&o); o2)
390  processed = filterScan3D(*o2, out, robotPose);
391  else if (auto o3 = dynamic_cast<const CObservationVelodyneScan*>(&o); o3)
392  processed = filterVelodyneScan(*o3, out, robotPose);
393 
394  // done?
395  if (processed)
396  {
397  // o.unload(); // DON'T! We don't know who else is using the data
398  return true; // we are done.
399  }
400 
401  // Create if new: Append to existing layer, if already existed.
402  mrpt::maps::CPointsMap::Ptr outPc = GetOrCreatePointLayer(
403  out, params_.target_layer, false /*does not allow empty name*/,
404  "mrpt::maps::CSimplePointsMap" /* creation class if not existing */);
405 
406  ASSERT_(outPc);
407 
408  MRPT_LOG_DEBUG_FMT(
409  "Using output layer '%s' of type '%s'", params_.target_layer.c_str(),
410  outPc->GetRuntimeClass()->className);
411 
412  // Observation format:
413 
414  // Special case:
415  // unproject 3D points, if needed:
416  if (auto obs3D =
417  dynamic_cast<const mrpt::obs::CObservation3DRangeScan*>(&o);
418  obs3D && obs3D->points3D_x.empty())
419  {
420  mrpt::maps::CSimplePointsMap tmpMap;
421 
422  mrpt::obs::T3DPointsProjectionParams pp;
423  pp.takeIntoAccountSensorPoseOnRobot = true;
424  pp.robotPoseInTheWorld = robotPose;
425  const_cast<mrpt::obs::CObservation3DRangeScan*>(obs3D)->unprojectInto(
426  tmpMap, pp);
427 
428  outPc->insertAnotherMap(&tmpMap, mrpt::poses::CPose3D::Identity());
429 
430  return true;
431  }
432  else
433  {
434  // General case:
435  const bool insertDone = o.insertObservationInto(*outPc, robotPose);
436 
438  {
439  THROW_EXCEPTION_FMT(
440  "Observation of type '%s' could not be converted into a "
441  "point cloud, and none of the specializations handled it, "
442  "so I do not know what to do with this observation!",
443  obsClassName);
444  }
445  return insertDone;
446  }
447 
448  // o.unload(); // DON'T! We don't know who else is using the data
449 }
450 
452  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
453  const std::optional<mrpt::poses::CPose3D>& robotPose) const
454 {
455  using namespace std::string_literals;
456 
457  const auto obsClassName = o.GetRuntimeClass()->className;
458 
459  // Create if new: Append to existing layer, if already existed.
460  mrpt::maps::CMetricMap::Ptr outMap;
461 
462  if (auto itLy = out.layers.find(params_.target_layer);
463  itLy != out.layers.end())
464  {
465  outMap = itLy->second;
466  }
467  else
468  {
469  // insert new layer:
470  mrpt::maps::TSetOfMetricMapInitializers mapInits;
471 
472  const std::string cfgPrefix = "map"s;
473 
474  // Create from either a INI file or the YAML version of it:
476  {
477  // Load from INI file
478  // ------------------------------
479  ASSERT_FILE_EXISTS_(params_.metric_map_definition_ini_file);
480  mrpt::config::CConfigFile cfg(
482  mapInits.loadFromConfigFile(cfg, cfgPrefix);
483  }
484  else
485  {
486  // Load from YAML file (with parameterizable values)
487  // ------------------------------------------------------
488  ASSERT_(!params_.metric_map_definition.empty());
489  const auto& c = params_.metric_map_definition;
490 
491  // Build an in-memory INI file with the structure expected by
492  // loadFromConfigFile():
493  mrpt::config::CConfigFileMemory cfg;
494 
495  ASSERT_(c.has("class"));
496  const std::string mapClass = c["class"].as<std::string>();
497  cfg.write(cfgPrefix, mapClass + "_count"s, "1");
498 
499  // optional plugin module?
500  if (c.has("plugin"))
501  {
502  const auto moduleToLoad = c["plugin"].as<std::string>();
503  MRPT_LOG_DEBUG_STREAM(
504  "About to load user-defined plugin: " << moduleToLoad);
505  internalLoadUserPlugin(moduleToLoad);
506  }
507 
508  // fill the rest sub-sections:
509  for (const auto& [k, v] : c.asMap())
510  {
511  if (!v.isMap()) continue;
512  const auto keyVal = k.as<std::string>();
513  const auto sectName =
514  cfgPrefix + "_"s + mapClass + "_00_"s + keyVal;
515  for (const auto& [kk, vv] : v.asMap())
516  {
517  ASSERT_(kk.isScalar());
518  ASSERT_(vv.isScalar());
519 
520  cfg.write(
521  sectName, kk.as<std::string>(), vv.as<std::string>());
522  }
523  }
524 
525  MRPT_LOG_DEBUG_STREAM(
526  "Built INI-like block for layer '" << params_.target_layer
527  << "':\n"
528  << cfg.getContent());
529 
530  // parse it:
531  mapInits.loadFromConfigFile(cfg, cfgPrefix);
532  }
533 
534  // create the map:
535  mrpt::maps::CMultiMetricMap theMap;
536  theMap.setListOfMaps(mapInits);
537 
538  ASSERT_(theMap.maps.size() >= 1);
539  outMap = theMap.maps.at(0);
540 
541  out.layers[params_.target_layer] = outMap;
542  }
543 
544  ASSERT_(outMap);
545 
546  // user-given filters: Done *AFTER* creating the map, if needed.
547  if (obsClassName == "mrpt::obs::CObservationComment"s ||
548  !std::regex_match(obsClassName, process_class_names_regex_) ||
549  !std::regex_match(o.sensorLabel, process_sensor_labels_regex_))
550  {
551  MRPT_LOG_DEBUG_STREAM("Skipping this observation");
552  return false;
553  }
554 
555  // Observation format:
556  o.load();
557 
558  // Use virtual insert method:
559  const bool insertDone = o.insertObservationInto(*outMap, robotPose);
560 
562  {
563  THROW_EXCEPTION_FMT(
564  "Observation of type '%s' could not be converted inserted into "
565  "the map of type '%s', so I do not know what to do with this "
566  "observation!",
567  obsClassName, outMap->GetRuntimeClass()->className);
568  }
569 
570  // o.unload(); // DON'T! We don't know who else is using the data
571  return insertDone; // handled
572 }
573 
574 namespace
575 {
576 void safe_add_to_list(const std::string& path, std::vector<std::string>& lst)
577 {
578  if (mrpt::system::directoryExists(path)) lst.push_back(path);
579 }
580 
581 void from_env_var_to_list(
582  const std::string& env_var_name, std::vector<std::string>& lst,
583  const std::string& subStringPattern = {})
584 {
585 #if defined(_WIN32)
586  const auto delim = std::string(";");
587 #else
588  const auto delim = std::string(":");
589 #endif
590 
591  const auto additionalPaths = mrpt::get_env<std::string>(env_var_name);
592  std::vector<std::string> pathList;
593  mrpt::system::tokenize(additionalPaths, delim, pathList);
594 
595  // Append to list:
596  for (const auto& path : pathList)
597  {
598  if (!subStringPattern.empty() &&
599  path.find(subStringPattern) == std::string::npos)
600  continue;
601  safe_add_to_list(path, lst);
602  }
603 }
604 } // namespace
605 
606 void Generator::internalLoadUserPlugin(const std::string& moduleToLoad) const
607 {
608  std::string absPath;
609 
610  if (!fs::path(moduleToLoad).is_relative())
611  {
612  // already absolute:
613  ASSERT_FILE_EXISTS_(moduleToLoad);
614  absPath = moduleToLoad;
615  }
616  else
617  {
618  // search for it:
619  std::vector<std::string> lstPath;
620  from_env_var_to_list("LD_LIBRARY_PATH", lstPath);
621 
622  for (const auto& p : lstPath)
623  {
624  const auto fp = mrpt::system::pathJoin({p, moduleToLoad});
625  if (mrpt::system::fileExists(fp))
626  {
627  absPath = fp;
628  break;
629  }
630  }
631  if (absPath.empty())
632  {
633  THROW_EXCEPTION_FMT(
634  "Could not find '%s' anywhere under the LD_LIBRARY_PATH paths",
635  moduleToLoad.c_str());
636  }
637  }
638 
639 #if defined(__unix__)
640  // Check if already loaded?
641  {
642  void* handle = dlopen(absPath.c_str(), RTLD_NOLOAD);
643  if (handle != nullptr)
644  {
645  return; // skip. already loaded.
646  }
647  }
648  void* handle = dlopen(absPath.c_str(), RTLD_LAZY);
649 
650 #else
651  HMODULE handle = LoadLibrary(absPath.c_str());
652 #endif
653  if (handle == nullptr)
654  {
655  const char* err = dlerror();
656  if (!err) err = "(error calling dlerror())";
657  THROW_EXCEPTION(mrpt::format(
658  "Error loading module: `%s`\ndlerror(): `%s`", absPath.c_str(),
659  err));
660  }
661 
662  MRPT_LOG_DEBUG_FMT("Successfully loaded: `%s`", absPath.c_str());
663 }
mp2p_icp_filters::Generator::Parameters::metric_map_definition_ini_file
std::string metric_map_definition_ini_file
Definition: Generator.h:124
mp2p_icp_filters::Generator::internalLoadUserPlugin
void internalLoadUserPlugin(const std::string &moduleToLoad) const
Definition: Generator.cpp:606
mp2p_icp_filters::Generator::filterPointCloud
virtual bool filterPointCloud(const mrpt::maps::CPointsMap &pc, const mrpt::poses::CPose3D &sensorPose, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose) const
Definition: Generator.cpp:206
generators
static mp2p_icp_filters::GeneratorSet generators
Definition: apps/icp-run/main.cpp:133
mp2p_icp_filters::Generator::initialize
virtual void initialize(const mrpt::containers::yaml &cfg_block)
Definition: Generator.cpp:123
s
XmlRpcServer s
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp_filters::Generator
Definition: Generator.h:71
mp2p_icp_filters::Generator::Parameters::metric_map_definition
mrpt::containers::yaml metric_map_definition
Definition: Generator.h:131
mp2p_icp_filters::Generator::filterScan2D
virtual bool filterScan2D(const mrpt::obs::CObservation2DRangeScan &pc, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose) const
Definition: Generator.cpp:170
mp2p_icp_filters::Generator::filterScan3D
virtual bool filterScan3D(const mrpt::obs::CObservation3DRangeScan &pc, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose) const
Definition: Generator.cpp:198
mp2p_icp_filters::Generator::initialized_
bool initialized_
Definition: Generator.h:179
mrpt
Definition: LogRecord.h:100
mp2p_icp_filters::Generator::implProcessCustomMap
bool implProcessCustomMap(const mrpt::obs::CObservation &o, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt) const
Definition: Generator.cpp:451
mp2p_icp::pointcloud_sanity_check
bool pointcloud_sanity_check(const mrpt::maps::CPointsMap &pc, bool printWarnings=true)
Definition: pointcloud_sanity_check.cpp:19
pointcloud_sanity_check.h
Checks for consistent length of field vectors.
mp2p_icp_filters::Generator::process_class_names_regex_
std::regex process_class_names_regex_
Definition: Generator.h:180
mp2p_icp_filters::Generator::Parameters::process_class_names_regex
std::string process_class_names_regex
Definition: Generator.h:137
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::Generator::params_
Parameters params_
Definition: Generator.h:147
Generator.h
Base virtual class for point cloud filters.
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp_filters::Generator::filterVelodyneScan
virtual bool filterVelodyneScan(const mrpt::obs::CObservationVelodyneScan &pc, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose) const
Definition: Generator.cpp:178
kitti-run-seq.cfg
cfg
Definition: kitti-run-seq.py:7
mp2p_icp_filters::Generator::Parameters::throw_on_unhandled_observation_class
bool throw_on_unhandled_observation_class
Definition: Generator.h:144
mp2p_icp_filters::Generator::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, Generator &parent)
Definition: Generator.cpp:44
mp2p_icp_filters::Generator::Parameters::target_layer
std::string target_layer
Definition: Generator.h:105
mp2p_icp_filters::GeneratorSet
std::vector< Generator::Ptr > GeneratorSet
Definition: Generator.h:198
mp2p_icp_filters::GetOrCreatePointLayer
mrpt::maps::CPointsMap::Ptr GetOrCreatePointLayer(mp2p_icp::metric_map_t &m, const std::string &layerName, bool allowEmptyName=true, const std::string &classForLayerCreation="mrpt::maps::CSimplePointsMap")
Definition: GetOrCreatePointLayer.cpp:15
mp2p_icp_filters::Generator::implProcessDefault
bool implProcessDefault(const mrpt::obs::CObservation &o, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt) const
Definition: Generator.cpp:354
mp2p_icp_filters::Generator::Parameters::process_sensor_labels_regex
std::string process_sensor_labels_regex
Definition: Generator.h:142
mp2p_icp_filters::generators_from_yaml_file
GeneratorSet generators_from_yaml_file(const std::string &filename, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: Generator.cpp:342
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
mp2p_icp_filters::Generator::filterRotatingScan
virtual bool filterRotatingScan(const mrpt::obs::CObservationRotatingScan &pc, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose) const
Definition: Generator.cpp:247
mp2p_icp_filters::Generator::Generator
Generator()
Definition: Generator.cpp:42
mp2p_icp::Parameterizable::parseAndDeclareParameter
void parseAndDeclareParameter(const std::string &value, double &target)
Definition: Parameterizable.cpp:120
GetOrCreatePointLayer.h
Auxiliary function GetOrCreatePointLayer.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
mp2p_icp_filters::Generator::process
virtual bool process(const mrpt::obs::CObservation &input_raw, mp2p_icp::metric_map_t &inOut, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt) const
Definition: Generator.cpp:138
mp2p_icp_filters::Generator::process_sensor_labels_regex_
std::regex process_sensor_labels_regex_
Definition: Generator.h:181
mp2p_icp_filters::apply_generators
bool apply_generators(const GeneratorSet &generators, const mrpt::obs::CObservation &obs, mp2p_icp::metric_map_t &output, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt)
Definition: Generator.cpp:255
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
kitti-batch-convert.filename
filename
Definition: kitti-batch-convert.py:6
mp2p_icp_filters::generators_from_yaml
GeneratorSet generators_from_yaml(const mrpt::containers::yaml &c, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
Definition: Generator.cpp:310


mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:11