FilterAdjustTimestamps.cpp
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 #include <mrpt/containers/yaml.h>
15 
16 #include <optional>
17 
19 
20 using namespace mp2p_icp_filters;
21 
23  const mrpt::containers::yaml& c, FilterAdjustTimestamps& parent)
24 {
25  MCP_LOAD_REQ(c, pointcloud_layer);
26  MCP_LOAD_REQ(c, method);
27  MCP_LOAD_REQ(c, silently_ignore_no_timestamps);
28 
30 }
31 
33 {
34  mrpt::system::COutputLogger::setLoggerName("FilterAdjustTimestamps");
35 }
36 
37 void FilterAdjustTimestamps::initialize(const mrpt::containers::yaml& c)
38 {
39  MRPT_START
40 
41  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
42  params_.load_from_yaml(c, *this);
43 
44  MRPT_END
45 }
46 
48 {
49  MRPT_START
50 
52 
53  // In/out:
54  auto pcPtr = inOut.point_layer(params_.pointcloud_layer);
55  ASSERTMSG_(
56  pcPtr,
57  mrpt::format(
58  "Input point cloud layer '%s' was not found.", params_.pointcloud_layer.c_str()));
59 
60  auto& pc = *pcPtr;
61 
62  auto* TsPtr = pc.getPointsBufferRef_timestamp();
63 
64  if (TsPtr == nullptr || (TsPtr->empty() && !pc.empty()))
65  {
66  // we don't have timestamps:
68  {
69  MRPT_LOG_DEBUG_STREAM(
70  "Skipping time adjusting in input cloud '" << params_.pointcloud_layer
71  << "' with contents: " << pc.asString()
72  << " due to missing timestamps.");
73  return;
74  }
75  else
76  {
77  THROW_EXCEPTION_FMT(
78  "Cannot do time adjusting for input cloud '%s' "
79  "with contents: %s due to missing timestamps.",
80  params_.pointcloud_layer.c_str(), pc.asString().c_str());
81  }
82  }
83 
84  auto& Ts = *TsPtr;
85 
86  std::optional<float> minT, maxT;
87 
88  for (size_t i = 0; i < Ts.size(); i++)
89  {
90  const float t = Ts[i];
91 
92  if (!minT || t < *minT) minT = t;
93  if (!maxT || t > *maxT) maxT = t;
94  }
95  ASSERT_(minT && maxT);
96 
97  switch (params_.method)
98  {
100  {
101  const float dt = 0.5f * (*maxT + *minT) + params_.time_offset;
102  for (auto& t : Ts) t -= dt;
103  }
104  break;
106  {
107  const float dt = *minT + params_.time_offset;
108  for (auto& t : Ts) t -= dt;
109  }
110  break;
112  {
113  const float m = *minT;
114  const float k = *maxT != *minT ? 1.0f / (*maxT - *minT) : 1.0f;
115  for (auto& t : Ts) t = (t - m) * k + params_.time_offset;
116  }
117  break;
118 
119  default:
120  THROW_EXCEPTION("Unknown value for 'method'");
121  }
122 
123  MRPT_END
124 }
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:135
mp2p_icp_filters::FilterAdjustTimestamps::params_
Parameters params_
Definition: FilterAdjustTimestamps.h:77
kitti-run-seq.f
string f
Definition: kitti-run-seq.py:12
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterAdjustTimestamps::initialize
void initialize(const mrpt::containers::yaml &c) override
Definition: FilterAdjustTimestamps.cpp:37
FilterAdjustTimestamps.h
Normalizes point cloud timestamps.
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:607
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::EarliestIsZero
@ EarliestIsZero
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
DECLARE_PARAMETER_IN_OPT
#define DECLARE_PARAMETER_IN_OPT(__yaml, __variable, __object)
Definition: Parameterizable.h:148
mp2p_icp_filters
Definition: FilterAdjustTimestamps.h:19
t
geometry_msgs::TransformStamped t
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