Matcher_Points_Base.h
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  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/Matcher.h>
15 #include <mrpt/math/TPoint3D.h>
16 
17 #include <cstdlib>
18 #include <limits> // std::numeric_limits
19 #include <optional>
20 #include <vector>
21 
22 namespace mp2p_icp
23 {
32 {
33  public:
34  Matcher_Points_Base() = default;
35 
45  std::map<std::string, std::map<std::string, double>> weight_pt2pt_layers;
46 
48  uint64_t localPointsSampleSeed_ = 0;
49 
53 
57 
59  std::optional<std::size_t> kdtree_leaf_max_points_;
60 
79  void initialize(const mrpt::containers::yaml& params) override;
80 
83  {
84  public:
85  mrpt::math::TPoint3Df localMin{fMax, fMax, fMax};
86  mrpt::math::TPoint3Df localMax{-fMax, -fMax, -fMax};
87 
89  std::optional<std::vector<std::size_t>> idxs;
90 
92  mrpt::aligned_std_vector<float> x_locals, y_locals, z_locals;
93 
94  private:
95  static constexpr auto fMax = std::numeric_limits<float>::max();
96  };
97 
99  const mrpt::maps::CPointsMap& pcLocal,
100  const mrpt::poses::CPose3D& localPose,
101  const std::size_t maxLocalPoints = 0,
102  const uint64_t localPointsSampleSeed = 0);
103 
104  protected:
105  bool impl_match(
106  const metric_map_t& pcGlobal, const metric_map_t& pcLocal,
107  const mrpt::poses::CPose3D& localPose, const MatchContext& mc,
108  MatchState& ms, Pairings& out) const override final;
109 
110  private:
111  virtual void implMatchOneLayer(
112  const mrpt::maps::CMetricMap& pcGlobal,
113  const mrpt::maps::CPointsMap& pcLocal,
114  const mrpt::poses::CPose3D& localPose, MatchState& ms,
115  const layer_name_t& globalName, const layer_name_t& localName,
116  Pairings& out) const = 0;
117 };
118 
119 } // namespace mp2p_icp
mp2p_icp::Matcher_Points_Base::kdtree_leaf_max_points_
std::optional< std::size_t > kdtree_leaf_max_points_
Definition: Matcher_Points_Base.h:59
mp2p_icp::Matcher_Points_Base
Definition: Matcher_Points_Base.h:31
mp2p_icp
Definition: covariance.h:17
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud
Definition: Matcher_Points_Base.h:82
mp2p_icp::Matcher
Definition: Matcher.h:70
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::y_locals
mrpt::aligned_std_vector< float > y_locals
Definition: Matcher_Points_Base.h:92
mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedGlobalPoints_
bool allowMatchAlreadyMatchedGlobalPoints_
Definition: Matcher_Points_Base.h:56
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::fMax
static constexpr auto fMax
Definition: Matcher_Points_Base.h:95
mp2p_icp::Pairings
Definition: Pairings.h:94
mp2p_icp::Matcher_Points_Base::weight_pt2pt_layers
std::map< std::string, std::map< std::string, double > > weight_pt2pt_layers
Definition: Matcher_Points_Base.h:45
mp2p_icp::Matcher_Points_Base::allowMatchAlreadyMatchedPoints_
bool allowMatchAlreadyMatchedPoints_
Definition: Matcher_Points_Base.h:52
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::idxs
std::optional< std::vector< std::size_t > > idxs
Definition: Matcher_Points_Base.h:89
mp2p_icp::Matcher_Points_Base::implMatchOneLayer
virtual void implMatchOneLayer(const mrpt::maps::CMetricMap &pcGlobal, const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, MatchState &ms, const layer_name_t &globalName, const layer_name_t &localName, Pairings &out) const =0
mp2p_icp::Matcher_Points_Base::initialize
void initialize(const mrpt::containers::yaml &params) override
Definition: Matcher_Points_Base.cpp:123
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::z_locals
mrpt::aligned_std_vector< float > z_locals
Definition: Matcher_Points_Base.h:92
mp2p_icp::MatchState
Definition: Matcher.h:34
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::MatchContext
Definition: Matcher.h:26
mp2p_icp::Matcher_Points_Base::localPointsSampleSeed_
uint64_t localPointsSampleSeed_
Definition: Matcher_Points_Base.h:48
mp2p_icp::Matcher_Points_Base::impl_match
bool impl_match(const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &localPose, const MatchContext &mc, MatchState &ms, Pairings &out) const override final
Definition: Matcher_Points_Base.cpp:22
Matcher.h
Pointcloud matching generic base class.
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::localMax
mrpt::math::TPoint3Df localMax
Definition: Matcher_Points_Base.h:86
mp2p_icp::Matcher_Points_Base::Matcher_Points_Base
Matcher_Points_Base()=default
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::localMin
mrpt::math::TPoint3Df localMin
Definition: Matcher_Points_Base.h:85
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
mp2p_icp::Matcher_Points_Base::maxLocalPointsPerLayer_
uint64_t maxLocalPointsPerLayer_
Definition: Matcher_Points_Base.h:47
mp2p_icp::Matcher_Points_Base::TransformedLocalPointCloud::x_locals
mrpt::aligned_std_vector< float > x_locals
Definition: Matcher_Points_Base.h:92
mp2p_icp::Matcher_Points_Base::transform_local_to_global
static TransformedLocalPointCloud transform_local_to_global(const mrpt::maps::CPointsMap &pcLocal, const mrpt::poses::CPose3D &localPose, const std::size_t maxLocalPoints=0, const uint64_t localPointsSampleSeed=0)
Definition: Matcher_Points_Base.cpp:173


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