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 
68  const mrpt::containers::yaml& params)
69 {
70  std::stringstream ss;
71  params.printAsYAML(ss);
72  pm_icp_yaml_settings_ = ss.str();
73 }
74 
76  [[maybe_unused]] const metric_map_t& pcLocal,
77  [[maybe_unused]] const metric_map_t& pcGlobal,
78  [[maybe_unused]] const mrpt::math::TPose3D& initialGuessLocalWrtGlobal,
79  [[maybe_unused]] const Parameters& p, [[maybe_unused]] Results& result,
80  [[maybe_unused]] const std::optional<mrpt::poses::CPose3DPDFGaussianInf>&
81  prior,
82  [[maybe_unused]] const mrpt::optional_ref<LogRecord>& outputDebugInfo)
83 {
84  using namespace std::string_literals;
85 
86  MRPT_START
87 #if defined(MP2P_HAS_LIBPOINTMATCHER)
88 
89  ASSERT_EQUAL_(pcLocal.layers.size(), pcGlobal.layers.size());
90  ASSERT_(!pcLocal.empty() && !pcGlobal.empty());
91 
92  ASSERTMSG_(
93  !pm_icp_yaml_settings_.empty(),
94  "You must call initialize_derived() first, or initialize from a YAML "
95  "file with a `derived` section with the LibPointMathcer-specific "
96  "configuration.");
97 
98  ICP_State state(pcLocal, pcGlobal);
99 
102  mrpt::poses::CPose3D(initialGuessLocalWrtGlobal);
103  auto prev_solution = state.currentSolution.optimalPose;
104 
105  // Reset output:
106  result = Results();
107 
108  // Prepare output debug records:
109  std::optional<LogRecord> currentLog;
110 
111  const bool generateDebugRecord =
112  outputDebugInfo.has_value() || p.generateDebugFiles;
113 
114  if (generateDebugRecord)
115  {
116  currentLog.emplace();
117  currentLog->pcGlobal = pcGlobal.get_shared_from_this_or_clone();
118  currentLog->pcLocal = pcLocal.get_shared_from_this_or_clone();
119  currentLog->initialGuessLocalWrtGlobal = initialGuessLocalWrtGlobal;
120  currentLog->icpParameters = p;
121  }
122 
123  // Count of points:
124  ASSERT_(pcLocal.size() > 0);
125  ASSERT_(pcGlobal.size() > 0);
126 
127  using PM = PointMatcher<double>;
128  using DP = PM::DataPoints;
129 
130  // Load point clouds
131  const DP ptsLocal = pointsToPM(pcLocal);
132  const DP ptsGlobal = pointsToPM(pcGlobal);
133 
134  ASSERT_GT_(ptsLocal.getNbPoints(), 0);
135  ASSERT_GT_(ptsGlobal.getNbPoints(), 0);
136 
137  // Create the default ICP algorithm
138  PM::ICP icp;
139 
140  {
141  // load YAML config
142  std::stringstream ss;
143  ss << pm_icp_yaml_settings_;
144  ss.seekg(0);
145  icp.loadFromYaml(ss);
146  }
147 
148  int cloudDimension = ptsLocal.getEuclideanDim();
149  ASSERT_EQUAL_(cloudDimension, 3U);
150  ASSERT_EQUAL_(ptsLocal.getEuclideanDim(), ptsGlobal.getEuclideanDim());
151 
152  PM::TransformationParameters initTransfo =
153  initialGuessLocalWrtGlobal.getHomogeneousMatrix().asEigen();
154 
156 
157  if (!rigidTrans.checkParameters(initTransfo))
158  {
159  MRPT_LOG_WARN(
160  "Initial transformation is not rigid, SE(3) identity will be used");
161  initTransfo = PM::TransformationParameters::Identity(
162  cloudDimension + 1, cloudDimension + 1);
163  }
164 
165  const DP ptsLocalTf = rigidTrans.compute(ptsLocal, initTransfo);
166 
167  // Compute the transformation to express data in ref
169  try
170  {
171  T = icp(ptsLocalTf, ptsGlobal);
172 
173  // PM gives us the transformation wrt the initial transformation,
174  // since we already applied that transf. to the input point cloud!
176  mrpt::poses::CPose3D(initialGuessLocalWrtGlobal) +
177  mrpt::poses::CPose3D(mrpt::math::CMatrixDouble44(T));
178 
179  // result.quality = icp.errorMinimizer->getWeightedPointUsedRatio();
180  }
181  catch (const PM::ConvergenceError&)
182  {
183  // No good pairing candidates.
184  result.quality = 0;
185  }
186 
187  // Output in MP2P_ICP format:
188  if (!icp.transformationCheckers.empty())
189  result.nIterations =
190  icp.transformationCheckers.at(0)->getConditionVariables()[0];
191  else
192  result.nIterations = 1;
193 
194  // Quality:
195  result.quality = evaluate_quality(
196  quality_evaluators_, pcGlobal, pcLocal,
197  state.currentSolution.optimalPose, result.finalPairings);
198 
199  result.terminationReason = IterTermReason::Stalled;
200  result.optimalScale = 1.0;
201  result.optimal_tf.mean = state.currentSolution.optimalPose;
202 
204 
205  result.optimal_tf.cov = mp2p_icp::covariance(
206  result.finalPairings, result.optimal_tf.mean, covParams);
207 
208  // ----------------------------
209  // Log records
210  // ----------------------------
211  // Store results into log struct:
212  if (currentLog) currentLog->icpResult = result;
213 
214  // Save log to disk:
215  if (currentLog.has_value()) save_log_file(*currentLog, p);
216 
217  // return log info:
218  if (currentLog && outputDebugInfo.has_value())
219  outputDebugInfo.value().get() = std::move(currentLog.value());
220 
221 #else
222  THROW_EXCEPTION("This method requires MP2P built against libpointmatcher");
223 #endif
224  MRPT_END
225 }
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:596
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:236
mp2p_icp::ICP_LibPointmatcher::pm_icp_yaml_settings_
std::string pm_icp_yaml_settings_
Definition: ICP_LibPointmatcher.h:65
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:75
PointMatcher< float >
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
mp2p_icp::ICP::ICP_State::currentSolution
OptimalTF_Result currentSolution
Definition: ICP.h:255
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
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:652
mp2p_icp::ICP::ICP_State
Definition: ICP.h:245
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
IMPLEMENTS_MRPT_OBJECT
IMPLEMENTS_MRPT_OBJECT(QualityEvaluator_RangeImageSimilarity, QualityEvaluator, mp2p_icp) using namespace mp2p_icp
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:48
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:75
mp2p_icp::ICP::save_log_file
static void save_log_file(const LogRecord &log, const Parameters &p)
Definition: mp2p_icp/src/ICP.cpp:391
PointMatcher< float >::TransformationParameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Tue Jul 2 2024 02:47:25