Generator.h
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  * ------------------------------------------------------------------------- */
13 #pragma once
14 
16 #include <mp2p_icp/metricmap.h>
17 #include <mrpt/containers/yaml.h>
18 #include <mrpt/maps/CPointsMap.h>
19 #include <mrpt/obs/obs_frwds.h>
20 #include <mrpt/rtti/CObject.h>
21 #include <mrpt/system/COutputLogger.h>
22 
23 #include <regex>
24 #include <stdexcept>
25 
26 namespace mp2p_icp_filters
27 {
33 struct NotImplementedError : public std::runtime_error
34 {
35  // NotImplementedError() = default;
36  template <typename T>
37  NotImplementedError(T v) : std::runtime_error(v)
38  {
39  }
40 };
41 
71 class Generator : public mrpt::rtti::CObject, // RTTI support
72  public mrpt::system::COutputLogger, // Logging support
73  public mp2p_icp::Parameterizable // Dynamic parameters
74 {
75  DEFINE_MRPT_OBJECT(Generator, mp2p_icp_filters)
76 
77  public:
78  Generator();
79 
88  virtual void initialize(const mrpt::containers::yaml& cfg_block);
89 
94  virtual bool process(
95  const mrpt::obs::CObservation& input_raw, mp2p_icp::metric_map_t& inOut,
96  const std::optional<mrpt::poses::CPose3D>& robotPose =
97  std::nullopt) const;
98 
99  struct Parameters
100  {
101  void load_from_yaml(const mrpt::containers::yaml& c, Generator& parent);
102 
106 
125 
131  mrpt::containers::yaml metric_map_definition;
132 
138 
143 
145  };
146 
148 
151  protected:
152  // To be overrided in derived classes, if implemented:
154  virtual bool filterScan2D(
155  const mrpt::obs::CObservation2DRangeScan& pc,
157  const std::optional<mrpt::poses::CPose3D>& robotPose) const;
159  virtual bool filterScan3D(
160  const mrpt::obs::CObservation3DRangeScan& pc,
162  const std::optional<mrpt::poses::CPose3D>& robotPose) const;
164  virtual bool filterVelodyneScan(
165  const mrpt::obs::CObservationVelodyneScan& pc,
167  const std::optional<mrpt::poses::CPose3D>& robotPose) const;
169  virtual bool filterPointCloud(
170  const mrpt::maps::CPointsMap& pc,
171  const mrpt::poses::CPose3D& sensorPose, mp2p_icp::metric_map_t& out,
172  const std::optional<mrpt::poses::CPose3D>& robotPose) const;
174  virtual bool filterRotatingScan(
175  const mrpt::obs::CObservationRotatingScan& pc,
177  const std::optional<mrpt::poses::CPose3D>& robotPose) const;
178 
179  bool initialized_ = false;
182 
183  private:
184  bool implProcessDefault(
185  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
186  const std::optional<mrpt::poses::CPose3D>& robotPose =
187  std::nullopt) const;
188 
190  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
191  const std::optional<mrpt::poses::CPose3D>& robotPose =
192  std::nullopt) const;
193 
194  void internalLoadUserPlugin(const std::string& moduleToLoad) const;
195 };
196 
198 using GeneratorSet = std::vector<Generator::Ptr>;
199 
208 bool apply_generators(
209  const GeneratorSet& generators, const mrpt::obs::CObservation& obs,
210  mp2p_icp::metric_map_t& output,
211  const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt);
212 
215  const GeneratorSet& generators, const mrpt::obs::CObservation& obs,
216  const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt);
217 
222 bool apply_generators(
223  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf,
224  mp2p_icp::metric_map_t& output,
225  const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt);
226 
229  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf,
230  const std::optional<mrpt::poses::CPose3D>& robotPose = std::nullopt);
231 
237 [[nodiscard]] GeneratorSet generators_from_yaml(
238  const mrpt::containers::yaml& c,
239  const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO);
240 
249  const std::string& filename,
250  const mrpt::system::VerbosityLevel& vLevel = mrpt::system::LVL_INFO);
251 
254 } // namespace mp2p_icp_filters
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::Parameters
Definition: Generator.h:99
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
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
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_filters::Generator::process_class_names_regex_
std::regex process_class_names_regex_
Definition: Generator.h:180
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:58
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
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
mp2p_icp::Parameterizable
Definition: Parameterizable.h:85
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::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
mp2p_icp_filters::NotImplementedError
Definition: Generator.h:33
Parameterizable.h
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
std
mp2p_icp_filters::NotImplementedError::NotImplementedError
NotImplementedError(T v)
Definition: Generator.h:37
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
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 Sat Sep 14 2024 02:46:36