FilterDeskew.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  * ------------------------------------------------------------------------- */
15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/maps/CSimplePointsMap.h>
17 #include <mrpt/math/ops_containers.h> // dotProduct
18 #include <mrpt/poses/Lie/SO.h>
19 #include <mrpt/random/RandomGenerators.h>
20 #include <mrpt/version.h>
21 
22 #if MRPT_VERSION >= 0x020b04
23 #include <mrpt/maps/CPointsMapXYZIRT.h>
24 #endif
25 
26 #if defined(MP2P_HAS_TBB)
27 #include <tbb/parallel_for.h>
28 #endif
29 
32 
33 using namespace mp2p_icp_filters;
34 
36 {
37  mrpt::system::COutputLogger::setLoggerName("FilterDeskew");
38 }
39 
40 void FilterDeskew::initialize(const mrpt::containers::yaml& c)
41 {
42  MRPT_LOG_DEBUG_STREAM("Loading these params:\n" << c);
43 
44  MCP_LOAD_REQ(c, input_pointcloud_layer);
45  MCP_LOAD_REQ(c, output_pointcloud_layer);
46 
47  MCP_LOAD_OPT(c, silently_ignore_no_timestamps);
48  MCP_LOAD_OPT(c, output_layer_class);
49  MCP_LOAD_OPT(c, skip_deskew);
50 
51  ASSERT_(c.has("twist") && c["twist"].isSequence());
52  ASSERT_EQUAL_(c["twist"].asSequence().size(), 6UL);
53 
54  const auto yamlTwist = c["twist"].asSequence();
55 
56  for (int i = 0; i < 6; i++)
57  Parameterizable::parseAndDeclareParameter(
58  yamlTwist.at(i).as<std::string>(), twist[i]);
59 }
60 
62 {
63  MRPT_START
64 #if MRPT_VERSION >= 0x020b04
65 
67 
68  // Out:
69  ASSERT_(!output_pointcloud_layer.empty());
70 
71  // Create if new: Append to existing layer, if already existed.
72  mrpt::maps::CPointsMap::Ptr outPc = GetOrCreatePointLayer(
73  inOut, output_pointcloud_layer, false /*dont allow empty names*/,
75 
76  // In:
77  ASSERT_(!input_pointcloud_layer.empty());
78 
79  const mrpt::maps::CPointsMap* inPc = nullptr;
80  if (auto itLy = inOut.layers.find(input_pointcloud_layer);
81  itLy != inOut.layers.end())
82  {
83  inPc = mp2p_icp::MapToPointsMap(*itLy->second);
84  if (!inPc)
85  THROW_EXCEPTION_FMT(
86  "Layer '%s' must be of point cloud type.",
87  input_pointcloud_layer.c_str());
88 
89  outPc->reserve(outPc->size() + inPc->size());
90  }
91  else
92  {
93  // Input layer doesn't exist:
94  THROW_EXCEPTION_FMT(
95  "Input layer '%s' not found on input map.",
96  input_pointcloud_layer.c_str());
97  }
98 
99  // If the input is empty, just move on:
100  if (inPc->empty())
101  {
102  MRPT_LOG_DEBUG_STREAM(
103  "Silently ignoring empty input layer: '" << input_pointcloud_layer
104  << "'");
105  return;
106  }
107 
108  // mandatory fields:
109  const auto& xs = inPc->getPointsBufferRef_x();
110  const auto& ys = inPc->getPointsBufferRef_y();
111  const auto& zs = inPc->getPointsBufferRef_z();
112  const size_t n = xs.size();
113 
114  // optional fields:
115  const auto* Is = inPc->getPointsBufferRef_intensity();
116  const auto* Ts = inPc->getPointsBufferRef_timestamp();
117  const auto* Rs = inPc->getPointsBufferRef_ring();
118 
119  auto* out_Is = outPc->getPointsBufferRef_intensity();
120  auto* out_Rs = outPc->getPointsBufferRef_ring();
121  auto* out_Ts = outPc->getPointsBufferRef_timestamp();
122 
123  // Do we have input timestamps per point?
124  if (!Ts || Ts->empty() || skip_deskew)
125  {
126  // not possible to do de-skew:
128  {
129  // just copy all points, including all optional attributes:
130  for (size_t i = 0; i < n; i++) //
131  outPc->insertPointFrom(*inPc, i);
132 
133  MRPT_LOG_DEBUG_STREAM(
134  "Skipping de-skewing in input cloud '"
136  << "' with contents: " << inPc->asString());
137  }
138  else
139  {
140  THROW_EXCEPTION_FMT(
141  "Input layer '%s' does not contain per-point timestamps, "
142  "cannot do scan deskew. Set "
143  "'silently_ignore_no_timestamps=true' to skip de-skew."
144  "Input map contents: '%s'",
145  input_pointcloud_layer.c_str(), inPc->asString().c_str());
146  }
147  }
148  else
149  {
150  // Yes, we have timestamps, apply de-skew:
151  const size_t n0 = outPc->size();
152  outPc->resize(n0 + n);
153 
154  const auto v = mrpt::math::TVector3D(twist.vx, twist.vy, twist.vz);
155  const auto w = mrpt::math::TVector3D(twist.wx, twist.wy, twist.wz);
156 
157 #if defined(MP2P_HAS_TBB)
158  tbb::parallel_for(
159  static_cast<size_t>(0), n,
160  [&](size_t i)
161 #else
162  for (size_t i = 0; i < n; i++)
163 #endif
164  {
165  const auto pt = mrpt::math::TPoint3Df(xs[i], ys[i], zs[i]);
166  if (!(pt.x == 0 && pt.y == 0 && pt.z == 0))
167  {
168  // Forward integrate twist:
169  const mrpt::math::TVector3D v_dt = v * (*Ts)[i];
170  const mrpt::math::TVector3D w_dt = w * (*Ts)[i];
171 
172  const auto p =
173  mrpt::poses::CPose3D::FromRotationAndTranslation(
174  // Rotation: From Lie group SO(3) exponential:
175  mrpt::poses::Lie::SO<3>::exp(
176  mrpt::math::CVectorFixedDouble<3>(w_dt)),
177  // Translation: simple constant velocity model:
178  v_dt);
179 
180  const auto corrPt = p.composePoint(pt);
181 
182  outPc->setPointFast(n0 + i, corrPt.x, corrPt.y, corrPt.z);
183  if (Is && out_Is) (*out_Is)[n0 + i] = (*Is)[i];
184  if (Rs && out_Rs) (*out_Rs)[n0 + i] = (*Rs)[i];
185  if (Ts && out_Ts) (*out_Ts)[n0 + i] = (*Ts)[i];
186  }
187  }
188 #if defined(MP2P_HAS_TBB)
189  );
190 #endif
191  }
192 
193  outPc->mark_as_modified();
194 #else
195  THROW_EXCEPTION("This class requires MRPT >=v2.11.4");
196 #endif
197  MRPT_END
198 }
mp2p_icp::Parameterizable::checkAllParametersAreRealized
void checkAllParametersAreRealized() const
Definition: Parameterizable.cpp:138
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::filter
void filter(mp2p_icp::metric_map_t &inOut) const override
Definition: FilterDeskew.cpp:61
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDeskew, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp_filters::FilterDeskew::skip_deskew
bool skip_deskew
Definition: FilterDeskew.h:84
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::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:648
mp2p_icp_filters::FilterBase
Definition: FilterBase.h:46
mp2p_icp_filters::GetOrCreatePointLayer
mrpt::maps::CPointsMap::Ptr GetOrCreatePointLayer(mp2p_icp::metric_map_t &m, const std::string &layerName, bool allowEmptyName=true, const std::string &classForLayerCreation="mrpt::maps::CSimplePointsMap")
Definition: GetOrCreatePointLayer.cpp:15
mp2p_icp_filters::FilterDeskew::twist
mrpt::math::TTwist3D twist
Definition: FilterDeskew.h:90
boost::posix_time
GetOrCreatePointLayer.h
Auxiliary function GetOrCreatePointLayer.
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:49
FilterDeskew.h
Deskew (motion compensate) a pointcloud from a moving LIDAR.
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:76
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