FilterRemoveByVoxelOccupancy.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/containers/yaml.h>
17 #include <mrpt/maps/CVoxelMap.h>
18 
20  FilterRemoveByVoxelOccupancy, mp2p_icp_filters::FilterBase,
22 
23 using namespace mp2p_icp_filters;
24 
26  const mrpt::containers::yaml& c, FilterRemoveByVoxelOccupancy& parent)
27 {
28  MCP_LOAD_REQ(c, input_pointcloud_layer);
29  MCP_LOAD_REQ(c, input_voxel_layer);
30  MCP_LOAD_OPT(c, output_layer_static_objects);
31  MCP_LOAD_OPT(c, output_layer_dynamic_objects);
32 
34 }
35 
37 {
38  mrpt::system::COutputLogger::setLoggerName("FilterRemoveByVoxelOccupancy");
39 }
40 
41 void FilterRemoveByVoxelOccupancy::initialize(const mrpt::containers::yaml& c)
42 {
43  MRPT_START
44 
45  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
46  params_.load_from_yaml(c, *this);
47 
48  MRPT_END
49 }
50 
52 {
53  MRPT_START
54 
56 
57  ASSERT_LE_(params_.occupancy_threshold, 1.0);
58  ASSERT_GE_(params_.occupancy_threshold, 0.0);
59 
60  // In pts:
61  ASSERTMSG_(
62  inOut.layers.count(params_.input_pointcloud_layer) != 0,
63  mrpt::format(
64  "Input layer '%s' not found.",
66 
67  const auto mapPtr = inOut.layers.at(params_.input_pointcloud_layer);
68  ASSERT_(mapPtr);
69 
70  const auto pcPtr = mp2p_icp::MapToPointsMap(*mapPtr);
71  ASSERTMSG_(
72  pcPtr, mrpt::format(
73  "Input point cloud layer '%s' could not be converted into a "
74  "point cloud (class='%s')",
76  mapPtr->GetRuntimeClass()->className));
77 
78  // In voxels:
79  ASSERTMSG_(
80  inOut.layers.count(params_.input_voxel_layer) != 0,
81  mrpt::format(
82  "Input layer '%s' not found.", params_.input_voxel_layer.c_str()));
83 
84  const auto voxelMapPtr = inOut.layers.at(params_.input_voxel_layer);
85  ASSERT_(voxelMapPtr);
86 
87  const auto voxelPtr =
88  std::dynamic_pointer_cast<mrpt::maps::CVoxelMap>(voxelMapPtr);
89  ASSERTMSG_(
90  voxelPtr, mrpt::format(
91  "Input voxel layer '%s' not of type mrpt::maps::CVoxelMap"
92  "(actual class='%s')",
93  params_.input_voxel_layer.c_str(),
94  voxelMapPtr->GetRuntimeClass()->className));
95 
96  // Outputs:
97  // Create if new: Append to existing layer, if already existed.
98  mrpt::maps::CPointsMap::Ptr outPcStatic = GetOrCreatePointLayer(
100  /*allow empty name for nullptr*/
101  true,
102  /* create cloud of the same type */
103  pcPtr->GetRuntimeClass()->className);
104  if (outPcStatic)
105  outPcStatic->reserve(outPcStatic->size() + pcPtr->size() / 2);
106 
107  mrpt::maps::CPointsMap::Ptr outPcDynamic = GetOrCreatePointLayer(
109  /*allow empty name for nullptr*/
110  true,
111  /* create cloud of the same type */
112  pcPtr->GetRuntimeClass()->className);
113  if (outPcDynamic)
114  outPcDynamic->reserve(outPcDynamic->size() + pcPtr->size() / 2);
115 
116  ASSERTMSG_(
117  outPcStatic || outPcDynamic,
118  "At least one 'output_layer_static_objects' or "
119  "'output_layer_dynamic_objects' output layers must be provided.");
120 
121  // Process occupancy input value so it lies within [0,0.5]:
122  const double occFree = params_.occupancy_threshold > 0.5
123  ? (1.0 - params_.occupancy_threshold)
125  const double occThres = 1.0 - occFree;
126 
127  // Process:
128  const auto& xs = pcPtr->getPointsBufferRef_x();
129  const auto& ys = pcPtr->getPointsBufferRef_y();
130  const auto& zs = pcPtr->getPointsBufferRef_z();
131  const size_t N = xs.size();
132 
133  size_t nStatic = 0, nDynamic = 0;
134 
135  for (size_t i = 0; i < N; i++)
136  {
137  double prob_occupancy = 0.5;
138  bool withinMap =
139  voxelPtr->getPointOccupancy(xs[i], ys[i], zs[i], prob_occupancy);
140  if (!withinMap) continue; // undefined! pt out of voxelmap
141 
142  mrpt::maps::CPointsMap* trgMap = nullptr;
143 
144  if (prob_occupancy > occThres)
145  {
146  trgMap = outPcStatic.get();
147  nDynamic++;
148  }
149  else if (prob_occupancy < occFree)
150  {
151  trgMap = outPcDynamic.get();
152  nStatic++;
153  }
154 
155  if (!trgMap) continue;
156 
157  trgMap->insertPointFrom(*pcPtr, i);
158  }
159 
160  MRPT_LOG_DEBUG_STREAM(
161  "Parsed " << N << " points: static=" << nStatic
162  << ", dynamic=" << nDynamic);
163 
164  MRPT_END
165 }
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:138
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::Parameters::occupancy_threshold
double occupancy_threshold
Definition: FilterRemoveByVoxelOccupancy.h:63
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::params_
Parameters params_
Definition: FilterRemoveByVoxelOccupancy.h:67
DECLARE_PARAMETER_IN_REQ
#define DECLARE_PARAMETER_IN_REQ(__yaml, __variable, __object)
Definition: Parameterizable.h:167
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:648
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
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::FilterRemoveByVoxelOccupancy::Parameters::input_voxel_layer
std::string input_voxel_layer
Definition: FilterRemoveByVoxelOccupancy.h:60
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterRemoveByVoxelOccupancy, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::Parameters::output_layer_dynamic_objects
std::string output_layer_dynamic_objects
Definition: FilterRemoveByVoxelOccupancy.h:62
mp2p_icp_filters::FilterRemoveByVoxelOccupancy
Definition: FilterRemoveByVoxelOccupancy.h:41
FilterRemoveByVoxelOccupancy.h
Removes points from an input point cloud layer by occupancy of another input voxel layer....
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterRemoveByVoxelOccupancy &parent)
Definition: FilterRemoveByVoxelOccupancy.cpp:25
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::Parameters::output_layer_static_objects
std::string output_layer_static_objects
Definition: FilterRemoveByVoxelOccupancy.h:61
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::FilterRemoveByVoxelOccupancy::Parameters::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterRemoveByVoxelOccupancy.h:59
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::FilterRemoveByVoxelOccupancy
FilterRemoveByVoxelOccupancy()
Definition: FilterRemoveByVoxelOccupancy.cpp:36
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterRemoveByVoxelOccupancy.cpp:51
mp2p_icp_filters::FilterRemoveByVoxelOccupancy::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterRemoveByVoxelOccupancy.cpp:41


mp2p_icp
Author(s):
autogenerated on Thu Oct 17 2024 02:45:33