ICP_LibPointmatcher.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 <mp2p_icp/covariance.h>
16 #include <mrpt/core/exceptions.h>
17 #include <mrpt/maps/CPointsMap.h>
18 #include <mrpt/poses/Lie/SE.h>
19 #include <mrpt/tfest/se3.h>
20 
21 #include <fstream>
22 #include <sstream>
23 
24 #if defined(MP2P_HAS_LIBPOINTMATCHER)
25 #include <pointmatcher/IO.h>
29 #endif
30 
32 
33 using namespace mp2p_icp;
34 
36 {
37 #if defined(MP2P_HAS_LIBPOINTMATCHER)
38  return true;
39 #else
40  return false;
41 #endif
42 }
43 
44 #if defined(MP2P_HAS_LIBPOINTMATCHER)
45 static PointMatcher<double>::DataPoints pointsToPM(const metric_map_t& pc)
46 {
47  // TODO: Convert pointclouds in a more efficient way (!)
48  std::stringstream ss;
49 
50  for (const auto& ly : pc.layers)
51  {
52  // const std::string& name = ly.first;
53  auto pts = mp2p_icp::MapToPointsMap(*ly.second);
54  if (!pts) continue; // Not a point cloud layer
55 
56  const auto xs = pts->getPointsBufferRef_x();
57  const auto ys = pts->getPointsBufferRef_y();
58  const auto zs = pts->getPointsBufferRef_z();
59  for (size_t i = 0; i < xs.size(); i++)
60  ss << mrpt::format("%f %f %f\n", xs[i], ys[i], zs[i]);
61  }
62  ss.seekg(0);
64 }
65 #endif
66 
67 void ICP_LibPointmatcher::initialize_derived(const mrpt::containers::yaml& params)
68 {
69  std::stringstream ss;
70  params.printAsYAML(ss);
71  pm_icp_yaml_settings_ = ss.str();
72 }
73 
75  [[maybe_unused]] const metric_map_t& pcLocal, [[maybe_unused]] const metric_map_t& pcGlobal,
76  [[maybe_unused]] const mrpt::math::TPose3D& initialGuessLocalWrtGlobal,
77  [[maybe_unused]] const Parameters& p, [[maybe_unused]] Results& result,
78  [[maybe_unused]] const std::optional<mrpt::poses::CPose3DPDFGaussianInf>& prior,
79  [[maybe_unused]] const mrpt::optional_ref<LogRecord>& outputDebugInfo)
80 {
81  using namespace std::string_literals;
82 
83  MRPT_START
84 #if defined(MP2P_HAS_LIBPOINTMATCHER)
85 
86  ASSERT_EQUAL_(pcLocal.layers.size(), pcGlobal.layers.size());
87  ASSERT_(!pcLocal.empty() && !pcGlobal.empty());
88 
89  ASSERTMSG_(
90  !pm_icp_yaml_settings_.empty(),
91  "You must call initialize_derived() first, or initialize from a YAML "
92  "file with a `derived` section with the LibPointMathcer-specific "
93  "configuration.");
94 
95  ICP_State state(pcLocal, pcGlobal);
96 
98  state.currentSolution.optimalPose = mrpt::poses::CPose3D(initialGuessLocalWrtGlobal);
99  auto prev_solution = state.currentSolution.optimalPose;
100 
101  // Reset output:
102  result = Results();
103 
104  // Prepare output debug records:
105  std::optional<LogRecord> currentLog;
106 
107  const bool generateDebugRecord = outputDebugInfo.has_value() || p.generateDebugFiles;
108 
109  if (generateDebugRecord)
110  {
111  currentLog.emplace();
112  currentLog->pcGlobal = pcGlobal.get_shared_from_this_or_clone();
113  currentLog->pcLocal = pcLocal.get_shared_from_this_or_clone();
114  currentLog->initialGuessLocalWrtGlobal = initialGuessLocalWrtGlobal;
115  currentLog->icpParameters = p;
116  }
117 
118  // Count of points:
119  ASSERT_(pcLocal.size() > 0);
120  ASSERT_(pcGlobal.size() > 0);
121 
122  using PM = PointMatcher<double>;
123  using DP = PM::DataPoints;
124 
125  // Load point clouds
126  const DP ptsLocal = pointsToPM(pcLocal);
127  const DP ptsGlobal = pointsToPM(pcGlobal);
128 
129  ASSERT_GT_(ptsLocal.getNbPoints(), 0);
130  ASSERT_GT_(ptsGlobal.getNbPoints(), 0);
131 
132  // Create the default ICP algorithm
133  PM::ICP icp;
134 
135  {
136  // load YAML config
137  std::stringstream ss;
138  ss << pm_icp_yaml_settings_;
139  ss.seekg(0);
140  icp.loadFromYaml(ss);
141  }
142 
143  int cloudDimension = ptsLocal.getEuclideanDim();
144  ASSERT_EQUAL_(cloudDimension, 3U);
145  ASSERT_EQUAL_(ptsLocal.getEuclideanDim(), ptsGlobal.getEuclideanDim());
146 
147  PM::TransformationParameters initTransfo =
148  initialGuessLocalWrtGlobal.getHomogeneousMatrix().asEigen();
149 
151 
152  if (!rigidTrans.checkParameters(initTransfo))
153  {
154  MRPT_LOG_WARN("Initial transformation is not rigid, SE(3) identity will be used");
155  initTransfo =
156  PM::TransformationParameters::Identity(cloudDimension + 1, cloudDimension + 1);
157  }
158 
159  const DP ptsLocalTf = rigidTrans.compute(ptsLocal, initTransfo);
160 
161  // Compute the transformation to express data in ref
163  try
164  {
165  T = icp(ptsLocalTf, ptsGlobal);
166 
167  // PM gives us the transformation wrt the initial transformation,
168  // since we already applied that transf. to the input point cloud!
169  state.currentSolution.optimalPose = mrpt::poses::CPose3D(initialGuessLocalWrtGlobal) +
170  mrpt::poses::CPose3D(mrpt::math::CMatrixDouble44(T));
171 
172  // result.quality = icp.errorMinimizer->getWeightedPointUsedRatio();
173  }
174  catch (const PM::ConvergenceError&)
175  {
176  // No good pairing candidates.
177  result.quality = 0;
178  }
179 
180  // Output in MP2P_ICP format:
181  if (!icp.transformationCheckers.empty())
182  result.nIterations = icp.transformationCheckers.at(0)->getConditionVariables()[0];
183  else
184  result.nIterations = 1;
185 
186  // Quality:
187  result.quality = evaluate_quality(
188  quality_evaluators_, pcGlobal, pcLocal, state.currentSolution.optimalPose,
189  result.finalPairings);
190 
191  result.terminationReason = IterTermReason::Stalled;
192  result.optimalScale = 1.0;
193  result.optimal_tf.mean = state.currentSolution.optimalPose;
194 
196 
197  result.optimal_tf.cov =
198  mp2p_icp::covariance(result.finalPairings, result.optimal_tf.mean, covParams);
199 
200  // ----------------------------
201  // Log records
202  // ----------------------------
203  // Store results into log struct:
204  if (currentLog) currentLog->icpResult = result;
205 
206  // Save log to disk:
207  if (currentLog.has_value()) save_log_file(*currentLog, p);
208 
209  // return log info:
210  if (currentLog && outputDebugInfo.has_value())
211  outputDebugInfo.value().get() = std::move(currentLog.value());
212 
213 #else
214  THROW_EXCEPTION("This method requires MP2P built against libpointmatcher");
215 #endif
216  MRPT_END
217 }
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp::IterTermReason::Stalled
@ Stalled
mp2p_icp
Definition: covariance.h:17
LoggerImpl.h
mp2p_icp::ICP::evaluate_quality
static double evaluate_quality(const quality_eval_list_t &evaluators, const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const Pairings &finalPairings)
Definition: mp2p_icp/src/ICP.cpp:566
PointMatcher::DataPoints::getEuclideanDim
unsigned getEuclideanDim() const
Return the dimension of the point cloud.
Definition: pointmatcher/DataPoints.cpp:165
TransformationsImpl::RigidTransformation::compute
virtual DataPoints compute(const DataPoints &input, const TransformationParameters &parameters) const
RigidTransformation.
Definition: TransformationsImpl.cpp:50
mp2p_icp::CovarianceParameters
Definition: covariance.h:19
ICP_LibPointmatcher.h
ICP wrapper on libpointmatcher.
mp2p_icp::ICP::quality_evaluators_
quality_eval_list_t quality_evaluators_
Definition: ICP.h:224
mp2p_icp::ICP_LibPointmatcher::pm_icp_yaml_settings_
std::string pm_icp_yaml_settings_
Definition: ICP_LibPointmatcher.h:62
mp2p_icp::ICP_LibPointmatcher::align
void align(const metric_map_t &pcLocal, const metric_map_t &pcGlobal, const mrpt::math::TPose3D &initialGuessLocalWrtGlobal, const Parameters &p, Results &result, const std::optional< mrpt::poses::CPose3DPDFGaussianInf > &prior=std::nullopt, const mrpt::optional_ref< LogRecord > &outputDebugInfo=std::nullopt) override
Definition: ICP_LibPointmatcher.cpp:74
PointMatcher< float >
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
mp2p_icp::ICP::ICP_State::currentSolution
OptimalTF_Result currentSolution
Definition: ICP.h:242
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(FilterDecimateVoxelsQuadratic, mp2p_icp_filters::FilterBase, mp2p_icp_filters) using namespace mp2p_icp_filters
mp2p_icp::ICP
Definition: ICP.h:51
mp2p_icp::covariance
mrpt::math::CMatrixDouble66 covariance(const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
Definition: covariance.cpp:22
mp2p_icp::ICP_LibPointmatcher::methodAvailable
static bool methodAvailable()
Definition: ICP_LibPointmatcher.cpp:35
PointMatcherIO::loadCSV
static DataPoints loadCSV(const std::string &fileName)
Associate an external name to a DataPoints type of information.
Definition: pointmatcher/IO.cpp:408
Matcher_Points_DistanceThreshold.h
Pointcloud matcher: fixed distance thresholds.
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:624
mp2p_icp::ICP::ICP_State
Definition: ICP.h:232
mp2p_icp::ICP_LibPointmatcher::initialize_derived
void initialize_derived(const mrpt::containers::yaml &params) override
Definition: ICP_LibPointmatcher.cpp:67
TransformationsImpl::RigidTransformation::checkParameters
virtual bool checkParameters(const TransformationParameters &parameters) const
Ensure orthogonality of the rotation matrix.
Definition: TransformationsImpl.cpp:91
TransformationsImpl::RigidTransformation
Definition: TransformationsImpl.h:54
PointMatcher::DataPoints::getNbPoints
unsigned getNbPoints() const
Return the number of points contained in the point cloud.
Definition: pointmatcher/DataPoints.cpp:158
covariance.h
Covariance estimation methods for ICP results.
TransformationsImpl.h
mp2p_icp::ICP_LibPointmatcher
Definition: ICP_LibPointmatcher.h:29
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:55
mp2p_icp::Results
Definition: Results.h:21
mp2p_icp::Parameters
Definition: Parameters.h:26
PointMatcher.h
public interface
IO.h
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:82
mp2p_icp::ICP::save_log_file
static void save_log_file(const LogRecord &log, const Parameters &p)
Definition: mp2p_icp/src/ICP.cpp:375
PointMatcher< float >::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182


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