FilterDecimateVoxels.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 
15 #include <mp2p_icp/metricmap.h>
19 #include <mrpt/maps/CPointsMap.h>
20 #include <mrpt/typemeta/TEnumType.h>
21 
22 namespace mp2p_icp_filters
23 {
29 enum class DecimateMethod : uint8_t
30 {
32  FirstPoint = 0,
39 };
40 
67 {
68  DEFINE_MRPT_OBJECT(FilterDecimateVoxels, mp2p_icp_filters)
69  public:
71 
72  // See docs in base class.
73  void initialize(const mrpt::containers::yaml& c) override;
74 
75  // See docs in FilterBase
76  void filter(mp2p_icp::metric_map_t& inOut) const override;
77 
78  struct Parameters
79  {
80  void load_from_yaml(
81  const mrpt::containers::yaml& c, FilterDecimateVoxels& parent);
82 
85  std::vector<std::string> input_pointcloud_layer = {
87 
92 
95 
97  double voxel_filter_resolution = 1.0; // [m]
98 
103 
105  std::optional<double> flatten_to;
106 
110  };
111 
114 
115  private:
116  mutable std::optional<PointCloudToVoxelGrid> filter_grid_;
117  mutable std::optional<PointCloudToVoxelGridSingle> filter_grid_single_;
118 
119  bool useSingleGrid() const
120  {
122  }
123 };
124 
127 } // namespace mp2p_icp_filters
128 
129 MRPT_ENUM_TYPE_BEGIN_NAMESPACE(
131 MRPT_FILL_ENUM(DecimateMethod::FirstPoint);
132 MRPT_FILL_ENUM(DecimateMethod::ClosestToAverage);
133 MRPT_FILL_ENUM(DecimateMethod::VoxelAverage);
134 MRPT_FILL_ENUM(DecimateMethod::RandomPoint);
135 MRPT_ENUM_TYPE_END()
mp2p_icp_filters::FilterDecimateVoxels::Parameters::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDecimateVoxels.h:94
mp2p_icp_filters::FilterDecimateVoxels::Parameters::decimate_method
DecimateMethod decimate_method
Definition: FilterDecimateVoxels.h:109
mp2p_icp_filters::FilterDecimateVoxels::Parameters::flatten_to
std::optional< double > flatten_to
See description on top of this page.
Definition: FilterDecimateVoxels.h:105
mp2p_icp_filters::FilterDecimateVoxels::useSingleGrid
bool useSingleGrid() const
Definition: FilterDecimateVoxels.h:119
mp2p_icp_filters::DecimateMethod::RandomPoint
@ RandomPoint
mp2p_icp_filters::FilterDecimateVoxels::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDecimateVoxels.cpp:94
MRPT_FILL_ENUM
MRPT_ENUM_TYPE_BEGIN_NAMESPACE(mp2p_icp_filters, mp2p_icp_filters::DecimateMethod) MRPT_FILL_ENUM(DecimateMethod MRPT_FILL_ENUM(DecimateMethod::ClosestToAverage)
mp2p_icp_filters::DecimateMethod::VoxelAverage
@ VoxelAverage
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:58
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::DecimateMethod::ClosestToAverage
@ ClosestToAverage
mp2p_icp_filters::FilterDecimateVoxels::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterDecimateVoxels.cpp:72
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterDecimateVoxels
Definition: FilterDecimateVoxels.h:66
PointCloudToVoxelGrid.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters::FilterDecimateVoxels::filter_grid_
std::optional< PointCloudToVoxelGrid > filter_grid_
Definition: FilterDecimateVoxels.h:116
mp2p_icp_filters::FilterDecimateVoxels::Parameters::voxel_filter_resolution
double voxel_filter_resolution
Definition: FilterDecimateVoxels.h:97
mp2p_icp_filters::FilterDecimateVoxels::FilterDecimateVoxels
FilterDecimateVoxels()
Definition: FilterDecimateVoxels.cpp:67
mp2p_icp_filters::FilterDecimateVoxels::Parameters::error_on_missing_input_layer
bool error_on_missing_input_layer
Definition: FilterDecimateVoxels.h:91
FilterBase.h
Base virtual class for point cloud filters.
mp2p_icp_filters::FilterDecimateVoxels::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterDecimateVoxels &parent)
Definition: FilterDecimateVoxels.cpp:29
mp2p_icp_filters::FilterDecimateVoxels::params_
Parameters params_
Definition: FilterDecimateVoxels.h:113
mp2p_icp_filters::FilterDecimateVoxels::filter_grid_single_
std::optional< PointCloudToVoxelGridSingle > filter_grid_single_
Definition: FilterDecimateVoxels.h:117
metricmap.h
Generic representation of pointcloud(s) and/or extracted features.
mp2p_icp_filters::FilterDecimateVoxels::Parameters
Definition: FilterDecimateVoxels.h:78
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
PointCloudToVoxelGridSingle.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters::FilterDecimateVoxels::Parameters::minimum_input_points_to_filter
uint32_t minimum_input_points_to_filter
Definition: FilterDecimateVoxels.h:102
mp2p_icp_filters::FilterDecimateVoxels::Parameters::input_pointcloud_layer
std::vector< std::string > input_pointcloud_layer
Definition: FilterDecimateVoxels.h:85
mp2p_icp_filters::DecimateMethod::FirstPoint
@ FirstPoint
mp2p_icp_filters::DecimateMethod
DecimateMethod
Definition: FilterDecimateVoxels.h:29
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19


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