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-2021 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 {
38 {
39  DEFINE_MRPT_OBJECT(FilterDecimateVoxels, mp2p_icp_filters)
40  public:
42 
43  // See docs in base class.
44  void initialize(const mrpt::containers::yaml& c) override;
45 
46  // See docs in FilterBase
47  void filter(mp2p_icp::metric_map_t& inOut) const override;
48 
49  struct Parameters
50  {
51  void load_from_yaml(const mrpt::containers::yaml& c);
52 
55 
60 
63 
65  double voxel_filter_resolution = .20; // [m]
66 
69  bool use_voxel_average = false;
70 
78  mrpt::math::TBoundingBoxf bounding_box = {
79  {-10.0f, -10.0f, -5.0f}, {10.0f, 10.0f, 5.0f}};
80  };
81 
84 
85  private:
87 };
88 
91 } // namespace mp2p_icp_filters
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
void load_from_yaml(const mrpt::containers::yaml &c)
Base virtual class for point cloud filters.
::std::string string
Definition: gtest.h:1979
void filter(mp2p_icp::metric_map_t &inOut) const override
Generic representation of pointcloud(s) and/or extracted features.
static constexpr const char * PT_LAYER_RAW
Definition: metricmap.h:56
Makes an index of a point cloud using a voxel grid.
void initialize(const mrpt::containers::yaml &c) override


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:05:09