FilterAdjustTimestamps.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>
17 #include <mrpt/typemeta/TEnumType.h>
18 
20 {
26 enum class TimestampAdjustMethod : uint8_t
27 {
30  EarliestIsZero = 0,
35  Normalize,
36 };
37 
47 {
48  DEFINE_MRPT_OBJECT(FilterAdjustTimestamps, mp2p_icp_filters)
49  public:
51 
52  // See docs in base class.
53  void initialize(const mrpt::containers::yaml& c) override;
54 
55  // See docs in FilterBase
56  void filter(mp2p_icp::metric_map_t& inOut) const override;
57 
58  struct Parameters
59  {
60  void load_from_yaml(const mrpt::containers::yaml& c, FilterAdjustTimestamps& parent);
61 
63 
68 
70  double time_offset = .0;
71 
74  };
75 
78 };
79 
81 } // namespace mp2p_icp_filters
82 
83 MRPT_ENUM_TYPE_BEGIN_NAMESPACE(mp2p_icp_filters, mp2p_icp_filters::TimestampAdjustMethod)
84 MRPT_FILL_ENUM(TimestampAdjustMethod::EarliestIsZero);
85 MRPT_FILL_ENUM(TimestampAdjustMethod::MiddleIsZero);
86 MRPT_FILL_ENUM(TimestampAdjustMethod::Normalize);
87 MRPT_ENUM_TYPE_END()
mp2p_icp_filters::FilterAdjustTimestamps::params_
Parameters params_
Definition: FilterAdjustTimestamps.h:77
mp2p_icp_filters::FilterAdjustTimestamps::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterAdjustTimestamps.cpp:47
mp2p_icp_filters::TimestampAdjustMethod::Normalize
@ Normalize
mp2p_icp_filters::FilterAdjustTimestamps::Parameters::silently_ignore_no_timestamps
bool silently_ignore_no_timestamps
Definition: FilterAdjustTimestamps.h:67
mp2p_icp_filters::FilterAdjustTimestamps::FilterAdjustTimestamps
FilterAdjustTimestamps()
Definition: FilterAdjustTimestamps.cpp:32
mp2p_icp_filters::FilterAdjustTimestamps::Parameters::load_from_yaml
void load_from_yaml(const mrpt::containers::yaml &c, FilterAdjustTimestamps &parent)
Definition: FilterAdjustTimestamps.cpp:22
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp_filters::FilterAdjustTimestamps::Parameters
Definition: FilterAdjustTimestamps.h:58
mp2p_icp_filters::FilterAdjustTimestamps::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterAdjustTimestamps.cpp:37
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::FilterAdjustTimestamps
Definition: FilterAdjustTimestamps.h:46
mp2p_icp_filters::FilterAdjustTimestamps::Parameters::pointcloud_layer
std::string pointcloud_layer
Definition: FilterAdjustTimestamps.h:62
mp2p_icp_filters::TimestampAdjustMethod
TimestampAdjustMethod
Definition: FilterAdjustTimestamps.h:26
FilterBase.h
Base virtual class for point cloud filters.
MRPT_FILL_ENUM
MRPT_FILL_ENUM(TimestampAdjustMethod::EarliestIsZero)
mp2p_icp_filters::TimestampAdjustMethod::EarliestIsZero
@ EarliestIsZero
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::FilterAdjustTimestamps::Parameters::method
TimestampAdjustMethod method
Definition: FilterAdjustTimestamps.h:73
mp2p_icp_filters::TimestampAdjustMethod::MiddleIsZero
@ MiddleIsZero
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
mp2p_icp_filters::FilterAdjustTimestamps::Parameters::time_offset
double time_offset
Definition: FilterAdjustTimestamps.h:70


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