GeneratorEdgesFromCurvature.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  * ------------------------------------------------------------------------- */
14 #include <mrpt/containers/yaml.h>
15 #include <mrpt/maps/CSimplePointsMap.h>
16 #include <mrpt/math/utils.h> // absDiff()
17 #include <mrpt/obs/CObservationRotatingScan.h>
18 #include <mrpt/version.h>
19 
20 #include <utility> // std::pair
21 
23 
24 using namespace mp2p_icp_filters;
25 
27  const mrpt::containers::yaml& c, GeneratorEdgesFromCurvature& parent)
28 {
31 }
32 
33 void GeneratorEdgesFromCurvature::initialize(const mrpt::containers::yaml& c)
34 {
35  // parent base method:
37 
38  paramsEdges_.load_from_yaml(c, *this);
39 }
40 
42  const mrpt::obs::CObservation& o, mp2p_icp::metric_map_t& out,
43  const std::optional<mrpt::poses::CPose3D>& robotPose) const
44 {
45  MRPT_START
46  using namespace mrpt::obs;
47 
48  ASSERTMSG_(initialized_, "initialize() must be called once before using process().");
49 
51 
52  const auto obsClassName = o.GetRuntimeClass()->className;
53 
54  // default: use point clouds:
55  ASSERT_(params_.metric_map_definition_ini_file.empty());
56 
57  bool processed = false;
58 
59  // user-given filters: Done *AFTER* creating the map, if needed.
60  if (!std::regex_match(obsClassName, process_class_names_regex_)) return false;
61  if (!std::regex_match(o.sensorLabel, process_sensor_labels_regex_)) return false;
62 
63  if (auto oRS = dynamic_cast<const CObservationRotatingScan*>(&o); oRS)
64  processed = filterRotatingScan(*oRS, out, robotPose);
65 
66  // done?
67  if (processed) return true; // we are done.
68 
69  // Create if new: Append to existing layer, if already existed.
70  mrpt::maps::CPointsMap::Ptr outPc;
71  if (auto itLy = out.layers.find(params_.target_layer); itLy != out.layers.end())
72  {
73  outPc = std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(itLy->second);
74  if (!outPc)
75  THROW_EXCEPTION_FMT(
76  "Layer '%s' must be of point cloud type.", params_.target_layer.c_str());
77  }
78  else
79  {
80  outPc = mrpt::maps::CSimplePointsMap::Create();
81  out.layers[params_.target_layer] = outPc;
82  }
83 
84  if (!outPc) outPc = mrpt::maps::CSimplePointsMap::Create();
85 
86  // Leave output point cloud empty, since it was not handled by the
87  // rotating scan handler above.
88 
89  return false;
90 
91  MRPT_END
92 }
93 
95  const mrpt::obs::CObservationRotatingScan& pc, mp2p_icp::metric_map_t& out,
96  const std::optional<mrpt::poses::CPose3D>& robotPose) const
97 {
98 #if MRPT_VERSION >= 0x020b04
99  auto outPc = mrpt::maps::CSimplePointsMap::Create();
100 
101  ASSERT_(!pc.organizedPoints.empty());
102 
103  const auto nRows = pc.rowCount;
104  const auto nCols = pc.columnCount;
105 
106  ASSERT_EQUAL_(nRows, pc.organizedPoints.rows());
107  ASSERT_EQUAL_(nCols, pc.organizedPoints.cols());
108 
109  ASSERT_EQUAL_(nRows, pc.rangeImage.rows());
110  ASSERT_EQUAL_(nCols, pc.rangeImage.cols());
111 
112  // for each row:
113  for (size_t r = 0; r < nRows; r++)
114  {
115  // compute range diff:
116  for (size_t i = 1; i + 1 < nCols; i++)
117  {
118  // we need at least 3 consecutive valid points:
119  if (!pc.rangeImage(r, i - 1) || !pc.rangeImage(r, i) || !pc.rangeImage(r, i + 1))
120  continue;
121 
122  const auto& pt_im1 = pc.organizedPoints(r, i - 1);
123  const auto& pt_i = pc.organizedPoints(r, i);
124  const auto& pt_ip1 = pc.organizedPoints(r, i + 1);
125 
126  const auto v1 = (pt_i - pt_im1);
127  const auto v2 = (pt_ip1 - pt_i);
128  const auto v1n = v1.norm();
129  const auto v2n = v2.norm();
130 
132  continue;
133 
134  const float score = v1.x * v2.x + v1.y * v2.y + v1.z * v2.z;
135 
136  if (std::abs(score) < paramsEdges_.max_cosine * v1n * v2n)
137  {
138  // this point passes:
139  if (robotPose)
140  outPc->insertPoint(robotPose->composePoint(pc.organizedPoints(r, i)));
141  else
142  outPc->insertPoint(pc.organizedPoints(r, i));
143  // TODO(jlbc) Output intensity?
144  }
145  }
146 
147  } // end for each row
148 
149  out.layers[params_.target_layer] = outPc;
150  return true; // Yes, it's implemented
151 #else
152  THROW_EXCEPTION("This class requires MRPT >=v2.11.4");
153 #endif
154 }
mp2p_icp_filters::GeneratorEdgesFromCurvature::filterRotatingScan
bool filterRotatingScan(const mrpt::obs::CObservationRotatingScan &pc, mp2p_icp::metric_map_t &out, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt) const override
Definition: GeneratorEdgesFromCurvature.cpp:94
mp2p_icp_filters::Generator::Parameters::metric_map_definition_ini_file
std::string metric_map_definition_ini_file
Definition: Generator.h:123
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:135
mp2p_icp_filters::GeneratorEdgesFromCurvature::process
bool process(const mrpt::obs::CObservation &input_raw, mp2p_icp::metric_map_t &inOut, const std::optional< mrpt::poses::CPose3D > &robotPose=std::nullopt) const override
Definition: GeneratorEdgesFromCurvature.cpp:41
mp2p_icp_filters::Generator::initialize
virtual void initialize(const mrpt::containers::yaml &cfg_block)
Definition: Generator.cpp:120
mp2p_icp_filters::Generator
Definition: Generator.h:71
mp2p_icp_filters::GeneratorEdgesFromCurvature::paramsEdges_
ParametersEdges paramsEdges_
Definition: GeneratorEdgesFromCurvature.h:46
mp2p_icp_filters::Generator::initialized_
bool initialized_
Definition: Generator.h:173
mp2p_icp_filters::GeneratorEdgesFromCurvature::ParametersEdges::max_cosine
float max_cosine
Definition: GeneratorEdgesFromCurvature.h:42
mp2p_icp_filters::GeneratorEdgesFromCurvature
Definition: GeneratorEdgesFromCurvature.h:25
mp2p_icp_filters::Generator::process_class_names_regex_
std::regex process_class_names_regex_
Definition: Generator.h:174
mp2p_icp_filters::Generator::params_
Parameters params_
Definition: Generator.h:146
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
DECLARE_PARAMETER_IN_REQ
#define DECLARE_PARAMETER_IN_REQ(__yaml, __variable, __object)
Definition: Parameterizable.h:155
mp2p_icp_filters::Generator::Parameters::target_layer
std::string target_layer
Definition: Generator.h:104
mp2p_icp_filters::GeneratorEdgesFromCurvature::ParametersEdges::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, GeneratorEdgesFromCurvature &parent)
Definition: GeneratorEdgesFromCurvature.cpp:26
mp2p_icp_filters::GeneratorEdgesFromCurvature::initialize
void initialize(const mrpt::containers::yaml &cfg_block) override
Definition: GeneratorEdgesFromCurvature.cpp:33
GeneratorEdgesFromCurvature.h
Generator of edge points from organized point clouds.
mp2p_icp_filters::GeneratorEdgesFromCurvature::ParametersEdges::min_point_clearance
float min_point_clearance
Definition: GeneratorEdgesFromCurvature.h:43
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
mp2p_icp_filters::Generator::process_sensor_labels_regex_
std::regex process_sensor_labels_regex_
Definition: Generator.h:175
DECLARE_PARAMETER_IN_OPT
#define DECLARE_PARAMETER_IN_OPT(__yaml, __variable, __object)
Definition: Parameterizable.h:148
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19


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