FilterVoxelSlice.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  * ------------------------------------------------------------------------- */
14 #pragma once
15 
16 #include <mp2p_icp/metricmap.h>
18 #include <mrpt/math/TPose3D.h>
19 
20 namespace mp2p_icp_filters
21 {
31 {
32  DEFINE_MRPT_OBJECT(FilterVoxelSlice, mp2p_icp_filters)
33  public:
35 
36  // See docs in base class.
37  void initialize(const mrpt::containers::yaml& c) override;
38 
39  // See docs in FilterBase
40  void filter(mp2p_icp::metric_map_t& inOut) const override;
41 
42  struct Parameters
43  {
44  void load_from_yaml(const mrpt::containers::yaml& c, FilterVoxelSlice& parent);
45 
48 
49  double slice_z_min = 0; // [m]
50  double slice_z_max = 0; // [m]
51  };
52 
55 };
56 
59 } // namespace mp2p_icp_filters
mp2p_icp_filters::FilterVoxelSlice::FilterVoxelSlice
FilterVoxelSlice()
Definition: FilterVoxelSlice.cpp:36
mp2p_icp_filters::FilterVoxelSlice::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterVoxelSlice &parent)
Definition: FilterVoxelSlice.cpp:26
mp2p_icp_filters::FilterVoxelSlice::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterVoxelSlice.cpp:51
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::FilterVoxelSlice::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterVoxelSlice.cpp:41
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterVoxelSlice::Parameters
Definition: FilterVoxelSlice.h:42
FilterBase.h
Base virtual class for point cloud filters.
mp2p_icp_filters::FilterVoxelSlice
Definition: FilterVoxelSlice.h:30
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::FilterVoxelSlice::Parameters::slice_z_min
double slice_z_min
Definition: FilterVoxelSlice.h:49
mp2p_icp_filters::FilterVoxelSlice::Parameters::output_layer
std::string output_layer
Definition: FilterVoxelSlice.h:47
mp2p_icp_filters::FilterVoxelSlice::params_
Parameters params_
Definition: FilterVoxelSlice.h:54
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterVoxelSlice::Parameters::slice_z_max
double slice_z_max
Definition: FilterVoxelSlice.h:50
mp2p_icp_filters::FilterVoxelSlice::Parameters::input_layer
std::string input_layer
Definition: FilterVoxelSlice.h:46


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