FilterDeskew.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/math/TTwist3D.h>
21 
22 namespace mp2p_icp_filters
23 {
40 {
41  DEFINE_MRPT_OBJECT(FilterDeskew, mp2p_icp_filters)
42  public:
43  FilterDeskew();
44 
59  void initialize(const mrpt::containers::yaml& c) override;
60 
61  // See docs in FilterBase
62  void filter(mp2p_icp::metric_map_t& inOut) const override;
63 
68 
71 
74  std::string output_layer_class = "mrpt::maps::CPointsMapXYZI";
75 
80 
84  bool skip_deskew = false;
85 
90  mrpt::math::TTwist3D twist;
91 };
92 
95 } // namespace mp2p_icp_filters
mp2p_icp_filters::FilterDeskew::output_layer_class
std::string output_layer_class
Definition: FilterDeskew.h:74
mp2p_icp_filters::FilterDeskew::FilterDeskew
FilterDeskew()
Definition: FilterDeskew.cpp:35
mp2p_icp_filters::FilterDeskew
Definition: FilterDeskew.h:39
mp2p_icp_filters::FilterDeskew::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDeskew.cpp:61
mp2p_icp_filters::FilterDeskew::skip_deskew
bool skip_deskew
Definition: FilterDeskew.h:84
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::FilterDeskew::silently_ignore_no_timestamps
bool silently_ignore_no_timestamps
Definition: FilterDeskew.h:79
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
PointCloudToVoxelGrid.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters::FilterDeskew::twist
mrpt::math::TTwist3D twist
Definition: FilterDeskew.h:90
FilterBase.h
Base virtual class for point cloud filters.
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:49
PointCloudToVoxelGridSingle.h
Makes an index of a point cloud using a voxel grid.
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterDeskew::input_pointcloud_layer
std::string input_pointcloud_layer
Definition: FilterDeskew.h:67
mp2p_icp_filters::FilterDeskew::output_pointcloud_layer
std::string output_pointcloud_layer
Definition: FilterDeskew.h:70
mp2p_icp_filters::FilterDeskew::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterDeskew.cpp:40


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