FilterDecimateAdaptive.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>
18 #include <mrpt/maps/CPointsMap.h>
19 
20 namespace mp2p_icp_filters
21 {
32 {
33  DEFINE_MRPT_OBJECT(FilterDecimateAdaptive, mp2p_icp_filters)
34  public:
36 
37  // See docs in base class.
38  void initialize(const mrpt::containers::yaml& c) override;
39 
40  // See docs in FilterBase
41  void filter(mp2p_icp::metric_map_t& inOut) const override;
42 
43  struct Parameters
44  {
45  void load_from_yaml(const mrpt::containers::yaml& c);
46 
47  bool enabled = true;
48 
50 
52 
53  unsigned int desired_output_point_count = 1000;
54 
58 
59  // These are used to automatically estimate the voxel size:
60  double assumed_minimum_pointcloud_bbox = 10.0; // [m]
62  };
63 
66 
67  private:
69 };
70 
73 } // namespace mp2p_icp_filters
mp2p_icp_filters::FilterDecimateAdaptive
Definition: FilterDecimateAdaptive.h:31
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::desired_output_point_count
unsigned int desired_output_point_count
Definition: FilterDecimateAdaptive.h:53
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterDecimateAdaptive.h:49
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::enabled
bool enabled
Definition: FilterDecimateAdaptive.h:47
mp2p_icp_filters::FilterDecimateAdaptive::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDecimateAdaptive.cpp:51
mp2p_icp_filters::FilterDecimateAdaptive::params_
Parameters params_
Definition: FilterDecimateAdaptive.h:65
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c)
Definition: FilterDecimateAdaptive.cpp:22
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::maximum_voxel_count_per_dimension
unsigned int maximum_voxel_count_per_dimension
Definition: FilterDecimateAdaptive.h:61
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:64
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::PointCloudToVoxelGrid
Definition: PointCloudToVoxelGrid.h:27
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDecimateAdaptive.h:51
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::assumed_minimum_pointcloud_bbox
double assumed_minimum_pointcloud_bbox
Definition: FilterDecimateAdaptive.h:60
mp2p_icp_filters::FilterDecimateAdaptive::Parameters
Definition: FilterDecimateAdaptive.h:43
mp2p_icp_filters::FilterDecimateAdaptive::FilterDecimateAdaptive
FilterDecimateAdaptive()
Definition: FilterDecimateAdaptive.cpp:36
PointCloudToVoxelGrid.h
Makes an index of a point cloud using a voxel grid.
FilterBase.h
Base virtual class for point cloud filters.
mp2p_icp_filters::FilterDecimateAdaptive::filter_grid_
PointCloudToVoxelGrid filter_grid_
Definition: FilterDecimateAdaptive.h:68
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:55
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterDecimateAdaptive::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterDecimateAdaptive.cpp:41
mp2p_icp_filters::FilterDecimateAdaptive::Parameters::minimum_input_points_per_voxel
unsigned int minimum_input_points_per_voxel
Definition: FilterDecimateAdaptive.h:57


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