15 #include <mrpt/containers/yaml.h>
16 #include <mrpt/maps/CSimplePointsMap.h>
17 #include <mrpt/math/ops_containers.h>
18 #include <mrpt/poses/Lie/SO.h>
19 #include <mrpt/random/RandomGenerators.h>
20 #include <mrpt/version.h>
22 #if MRPT_VERSION >= 0x020b04
23 #include <mrpt/maps/CPointsMapXYZIRT.h>
26 #if defined(MP2P_HAS_TBB)
27 #include <tbb/parallel_for.h>
37 mrpt::system::COutputLogger::setLoggerName(
"FilterDeskew");
42 MRPT_LOG_DEBUG_STREAM(
"Loading these params:\n" << c);
51 ASSERT_(c.has(
"twist") && c[
"twist"].isSequence());
52 ASSERT_EQUAL_(c[
"twist"].asSequence().size(), 6UL);
54 const auto yamlTwist = c[
"twist"].asSequence();
56 for (
int i = 0; i < 6; i++)
57 Parameterizable::parseAndDeclareParameter(
64 #if MRPT_VERSION >= 0x020b04
79 const mrpt::maps::CPointsMap* inPc =
nullptr;
81 itLy != inOut.
layers.end())
86 "Layer '%s' must be of point cloud type.",
89 outPc->reserve(outPc->size() + inPc->size());
95 "Input layer '%s' not found on input map.",
102 MRPT_LOG_DEBUG_STREAM(
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();
115 const auto* Is = inPc->getPointsBufferRef_intensity();
116 const auto* Ts = inPc->getPointsBufferRef_timestamp();
117 const auto* Rs = inPc->getPointsBufferRef_ring();
119 auto* out_Is = outPc->getPointsBufferRef_intensity();
120 auto* out_Rs = outPc->getPointsBufferRef_ring();
121 auto* out_Ts = outPc->getPointsBufferRef_timestamp();
130 for (
size_t i = 0; i < n; i++)
131 outPc->insertPointFrom(*inPc, i);
133 MRPT_LOG_DEBUG_STREAM(
134 "Skipping de-skewing in input cloud '"
136 <<
"' with contents: " << inPc->asString());
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'",
151 const size_t n0 = outPc->size();
152 outPc->resize(n0 + n);
157 #if defined(MP2P_HAS_TBB)
159 static_cast<size_t>(0), n,
162 for (
size_t i = 0; i < n; i++)
165 const auto pt = mrpt::math::TPoint3Df(xs[i], ys[i], zs[i]);
166 if (!(
pt.x == 0 &&
pt.y == 0 &&
pt.z == 0))
169 const mrpt::math::TVector3D v_dt = v * (*Ts)[i];
170 const mrpt::math::TVector3D w_dt = w * (*Ts)[i];
173 mrpt::poses::CPose3D::FromRotationAndTranslation(
175 mrpt::poses::Lie::SO<3>::exp(
176 mrpt::math::CVectorFixedDouble<3>(w_dt)),
180 const auto corrPt = p.composePoint(
pt);
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];
188 #if defined(MP2P_HAS_TBB)
193 outPc->mark_as_modified();
195 THROW_EXCEPTION(
"This class requires MRPT >=v2.11.4");