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-2021 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
14 #include <mrpt/containers/yaml.h>
15 #include <mrpt/maps/CSimplePointsMap.h>
16 #include <mrpt/obs/CObservation2DRangeScan.h>
17 #include <mrpt/obs/CObservation3DRangeScan.h>
18 #include <mrpt/obs/CObservationPointCloud.h>
19 #include <mrpt/obs/CObservationRotatingScan.h>
20 #include <mrpt/obs/CObservationVelodyneScan.h>
21 #include <mrpt/obs/CSensoryFrame.h>
22 #include <mrpt/version.h>
23 
25 
26 using namespace mp2p_icp_filters;
27 
28 Generator::Generator() : mrpt::system::COutputLogger("Generator") {}
29 
30 void Generator::Parameters::load_from_yaml(const mrpt::containers::yaml& c)
31 {
32  MCP_LOAD_OPT(c, target_pointcloud_layer);
33  MCP_LOAD_OPT(c, process_class_names_regex);
34  MCP_LOAD_OPT(c, process_sensor_labels_regex);
35  MCP_LOAD_OPT(c, throw_on_unhandled_observation_class);
36 }
37 
38 void Generator::initialize(const mrpt::containers::yaml& c)
39 {
40  MRPT_START
41 
42  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
44 
48 
49  initialized_ = true;
50  MRPT_END
51 }
52 
54  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out) const
55 {
56  MRPT_START
57  using namespace mrpt::obs;
58 
59  ASSERTMSG_(
61  "initialize() must be called once before using process().");
62 
63  const auto obsClassName = o.GetRuntimeClass()->className;
64 
65  // user-given filters:
66  if (!std::regex_match(obsClassName, process_class_names_regex_)) return;
67  if (!std::regex_match(o.sensorLabel, process_sensor_labels_regex_)) return;
68 
69  bool processed = false;
70 
71  if (auto o0 = dynamic_cast<const CObservationPointCloud*>(&o); o0)
72  {
73  ASSERT_(o0->pointcloud);
74  processed = filterPointCloud(*o0->pointcloud, out);
75  }
76  else if (auto o1 = dynamic_cast<const CObservation2DRangeScan*>(&o); o1)
77  processed = filterScan2D(*o1, out);
78  else if (auto o2 = dynamic_cast<const CObservation3DRangeScan*>(&o); o2)
79  processed = filterScan3D(*o2, out);
80  else if (auto o3 = dynamic_cast<const CObservationVelodyneScan*>(&o); o3)
81  processed = filterVelodyneScan(*o3, out);
82 
83  // done?
84  if (!processed)
85  {
86  // Create if new: Append to existing layer, if already existed.
87  mrpt::maps::CPointsMap::Ptr outPc;
88  if (auto itLy = out.layers.find(params_.target_pointcloud_layer);
89  itLy != out.layers.end())
90  {
91  outPc =
92  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itLy->second);
93  if (!outPc)
94  THROW_EXCEPTION_FMT(
95  "Layer '%s' must be of point cloud type.",
97  }
98  else
99  {
100  outPc = mrpt::maps::CSimplePointsMap::Create();
101  out.layers[params_.target_pointcloud_layer] = outPc;
102  }
103 
104  if (!outPc) outPc = mrpt::maps::CSimplePointsMap::Create();
105 
106  // Observation format:
107  o.load();
108 
109  // Special case:
110  // unproject 3D points, if needed:
111  if (auto obs3D =
112  dynamic_cast<const mrpt::obs::CObservation3DRangeScan*>(&o);
113  obs3D && obs3D->points3D_x.empty())
114  {
115  mrpt::maps::CSimplePointsMap tmpMap;
116 
117  mrpt::obs::T3DPointsProjectionParams pp;
118  pp.takeIntoAccountSensorPoseOnRobot = true;
119  const_cast<mrpt::obs::CObservation3DRangeScan*>(obs3D)
120  ->unprojectInto(tmpMap, pp);
121 
122  outPc->insertAnotherMap(&tmpMap, mrpt::poses::CPose3D::Identity());
123  }
124  else
125  {
126  // General case:
127 #if MRPT_VERSION >= 0x240
128  auto& thePc = *outPc;
129 #else
130  auto* thePc = outPc.get();
131 #endif
132  const bool insertDone = o.insertObservationInto(thePc);
133 
135  {
136  THROW_EXCEPTION_FMT(
137  "Observation of type '%s' could not be converted into a "
138  "point cloud, and none of the specializations handled it, "
139  "so I "
140  "do not know what to do with this observation!",
141  obsClassName);
142  }
143  }
144 
145 #if MRPT_VERSION >= 0x233
146  o.unload();
147 #else
148  // workaround to mrpt const correctness problem in <= v2.3.2
149  const_cast<mrpt::obs::CObservation&>(o).unload();
150 #endif
151  }
152 
153  MRPT_END
154 }
155 
157  [[maybe_unused]] const mrpt::obs::CObservation2DRangeScan& pc,
158  [[maybe_unused]] mp2p_icp::metric_map_t& out) const
159 {
160  return false; // Not implemented
161 }
162 
164  [[maybe_unused]] const mrpt::obs::CObservationVelodyneScan& pc,
165  [[maybe_unused]] mp2p_icp::metric_map_t& out) const
166 {
167  return false; // Not implemented
168 }
169 
171  [[maybe_unused]] const mrpt::obs::CObservation3DRangeScan& pc,
172  [[maybe_unused]] mp2p_icp::metric_map_t& out) const
173 {
174  return false; // Not implemented
175 }
176 
178  const mrpt::maps::CPointsMap& pc, mp2p_icp::metric_map_t& out) const
179 {
180  // Create if new: Append to existing layer, if already existed.
181  mrpt::maps::CPointsMap::Ptr outPc;
182  if (auto itLy = out.layers.find(params_.target_pointcloud_layer);
183  itLy != out.layers.end())
184  {
185  outPc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itLy->second);
186  if (!outPc)
187  THROW_EXCEPTION_FMT(
188  "Layer '%s' must be of point cloud type.",
190  }
191  else
192  {
193  outPc = mrpt::maps::CSimplePointsMap::Create();
194  out.layers[params_.target_pointcloud_layer] = outPc;
195  }
196 
197  outPc->insertAnotherMap(&pc, mrpt::poses::CPose3D::Identity());
198 
199  return true;
200 }
201 
203  [[maybe_unused]] const mrpt::obs::CObservationRotatingScan& pc,
204  [[maybe_unused]] mp2p_icp::metric_map_t& out) const
205 {
206  return false; // Not implemented
207 }
208 
210  const GeneratorSet& generators, const mrpt::obs::CObservation& obs,
211  mp2p_icp::metric_map_t& output)
212 {
213  ASSERT_(!generators.empty());
214  for (const auto& g : generators)
215  {
216  ASSERT_(g.get() != nullptr);
217  g->process(obs, output);
218  }
219 }
220 
222  const GeneratorSet& generators, const mrpt::obs::CObservation& obs)
223 {
225  apply_generators(generators, obs, pc);
226  return pc;
227 }
228 
230  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf)
231 {
233  apply_generators(generators, sf, pc);
234  return pc;
235 }
236 
238  const GeneratorSet& generators, const mrpt::obs::CSensoryFrame& sf,
239  mp2p_icp::metric_map_t& output)
240 {
241  ASSERT_(!generators.empty());
242  for (const auto& g : generators)
243  {
244  ASSERT_(g.get() != nullptr);
245  for (const auto& obs : sf)
246  {
247  if (!obs) continue;
248  g->process(*obs, output);
249  }
250  }
251 }
252 
254  const mrpt::containers::yaml& c, const mrpt::system::VerbosityLevel& vLevel)
255 {
256  if (c.isNullNode()) return {};
257 
258  ASSERT_(c.isSequence());
259 
261 
262  for (const auto& entry : c.asSequence())
263  {
264  const auto& e = entry.asMap();
265 
266  const auto sClass = e.at("class_name").as<std::string>();
267  auto o = mrpt::rtti::classFactory(sClass);
268  ASSERT_(o);
269 
270  auto f = std::dynamic_pointer_cast<Generator>(o);
271  ASSERTMSG_(
272  f, mrpt::format(
273  "`%s` class seems not to be derived from Generator",
274  sClass.c_str()));
275 
276  f->setMinLoggingLevel(vLevel);
277 
278  f->initialize(e.at("params"));
279  generators.push_back(f);
280  }
281 
282  return generators;
283 }
284 
286  const std::string& filename, const mrpt::system::VerbosityLevel& vLevel)
287 {
288  const auto yamlContent = mrpt::containers::yaml::FromFile(filename);
289 
290  ASSERT_(
291  yamlContent.has("generators") &&
292  yamlContent["generators"].isSequence());
293 
294  return generators_from_yaml(yamlContent["generators"], vLevel);
295 }
mp2p_icp_filters::Generator::filterPointCloud
virtual bool filterPointCloud(const mrpt::maps::CPointsMap &pc, mp2p_icp::metric_map_t &out) const
Definition: Generator.cpp:177
mp2p_icp_filters::Generator::initialize
virtual void initialize(const mrpt::containers::yaml &cfg_block)
Definition: Generator.cpp:38
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
mp2p_icp_filters::Generator
Definition: Generator.h:72
generators
static mp2p_icp_filters::GeneratorSet generators
Definition: apps/mp2p-icp-run/main.cpp:130
mp2p_icp_filters::Generator::initialized_
bool initialized_
Definition: Generator.h:147
mrpt
Definition: LogRecord.h:99
mp2p_icp_filters::Generator::process_class_names_regex_
std::regex process_class_names_regex_
Definition: Generator.h:148
mp2p_icp_filters::Generator::Parameters::process_class_names_regex
std::string process_class_names_regex
Definition: Generator.h:111
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::Generator::params_
Parameters params_
Definition: Generator.h:121
Generator.h
Base virtual class for point cloud filters.
mp2p_icp_filters::Generator::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c)
Definition: Generator.cpp:30
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp_filters::Generator::filterRotatingScan
virtual bool filterRotatingScan(const mrpt::obs::CObservationRotatingScan &pc, mp2p_icp::metric_map_t &out) const
Definition: Generator.cpp:202
mp2p_icp_filters::Generator::filterScan2D
virtual bool filterScan2D(const mrpt::obs::CObservation2DRangeScan &pc, mp2p_icp::metric_map_t &out) const
Definition: Generator.cpp:156
mp2p_icp_filters::Generator::Parameters::throw_on_unhandled_observation_class
bool throw_on_unhandled_observation_class
Definition: Generator.h:118
mp2p_icp_filters::apply_generators
void apply_generators(const GeneratorSet &generators, const mrpt::obs::CObservation &obs, mp2p_icp::metric_map_t &output)
Definition: Generator.cpp:209
mp2p_icp_filters::GeneratorSet
std::vector< Generator::Ptr > GeneratorSet
Definition: Generator.h:153
mp2p_icp_filters::Generator::Parameters::process_sensor_labels_regex
std::string process_sensor_labels_regex
Definition: Generator.h:116
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:285
mp2p_icp_filters::Generator::Generator
Generator()
Definition: Generator.cpp:28
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
mp2p_icp_filters::Generator::process
virtual void process(const mrpt::obs::CObservation &input_raw, mp2p_icp::metric_map_t &inOut) const
Definition: Generator.cpp:53
mp2p_icp_filters::Generator::Parameters::target_pointcloud_layer
std::string target_pointcloud_layer
Definition: Generator.h:104
mp2p_icp_filters::Generator::process_sensor_labels_regex_
std::regex process_sensor_labels_regex_
Definition: Generator.h:149
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(metric_map_t, mrpt::serialization::CSerializable, mp2p_icp) using namespace mp2p_icp
mp2p_icp_filters::Generator::filterScan3D
virtual bool filterScan3D(const mrpt::obs::CObservation3DRangeScan &pc, mp2p_icp::metric_map_t &out) const
Definition: Generator.cpp:170
mp2p_icp_filters::Generator::filterVelodyneScan
virtual bool filterVelodyneScan(const mrpt::obs::CObservationVelodyneScan &pc, mp2p_icp::metric_map_t &out) const
Definition: Generator.cpp:163
mp2p_icp_filters
Definition: FilterBase.h:25
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:253


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:02