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


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:03