metricmap.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-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
12 #pragma once
13 
14 #include <mp2p_icp/layer_name_t.h>
15 #include <mp2p_icp/plane_patch.h>
16 #include <mp2p_icp/render_params.h>
17 #include <mrpt/maps/CPointsMap.h>
18 #include <mrpt/maps/NearestNeighborsCapable.h>
19 #include <mrpt/math/TLine3D.h>
20 #include <mrpt/math/TPoint3D.h>
21 #include <mrpt/math/geometry.h>
22 #include <mrpt/poses/CPose3DPDFGaussian.h>
23 #include <mrpt/serialization/CSerializable.h>
24 #include <mrpt/topography/data_types.h>
25 
26 #include <map>
27 #include <memory>
28 #include <optional>
29 #include <string>
30 #include <vector>
31 
32 namespace mp2p_icp
33 {
48 class metric_map_t : public mrpt::serialization::CSerializable,
49  public std::enable_shared_from_this<metric_map_t>
50 {
51  DEFINE_SERIALIZABLE(metric_map_t, mp2p_icp)
52 
53  public:
57  constexpr static const char* PT_LAYER_RAW = "raw";
58  constexpr static const char* PT_LAYER_PLANE_CENTROIDS = "plane_centroids";
59 
75  std::map<layer_name_t, mrpt::maps::CMetricMap::Ptr> layers;
76 
78  std::vector<mrpt::math::TLine3D> lines;
79 
81  std::vector<plane_patch_t> planes;
82 
88  std::optional<uint64_t> id;
89 
96  std::optional<std::string> label;
97 
99  {
102  mrpt::topography::TGeodeticCoords geo_coord;
103 
111  mrpt::poses::CPose3DPDFGaussian T_enu_to_map;
112  };
113 
116  std::optional<Georeferencing> georeferencing;
117 
124  virtual bool empty() const;
125 
127  virtual size_t size() const;
128 
130  virtual size_t size_points_only() const;
131 
134  virtual std::string contents_summary() const;
135 
137  virtual void clear();
138 
143  bool save_to_file(const std::string& fileName) const;
144 
148  bool load_from_file(const std::string& fileName);
149 
159  mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t& name) const;
160 
170  virtual auto get_visualization(const render_params_t& p = render_params_t())
171  const -> std::shared_ptr<mrpt::opengl::CSetOfObjects>;
172 
181  virtual void merge_with(
182  const metric_map_t& otherPc,
183  const std::optional<mrpt::math::TPose3D>& otherRelativePose =
184  std::nullopt);
185 
188  mrpt::opengl::CSetOfObjects& o, const render_params_planes_t& p) const;
189 
192  mrpt::opengl::CSetOfObjects& o, const render_params_lines_t& p) const;
193 
196  mrpt::opengl::CSetOfObjects& o, const render_params_points_t& p) const;
197 
199  static void get_visualization_map_layer(
200  mrpt::opengl::CSetOfObjects& o, const render_params_point_layer_t& p,
201  const mrpt::maps::CMetricMap::Ptr& map);
202 
206  Ptr get_shared_from_this();
207 
212 
213  // const versions:
214  ConstPtr get_shared_from_this() const;
215  ConstPtr get_shared_from_this_or_clone() const;
216 
219  protected:
221  virtual void derivedSerializeTo(
222  [[maybe_unused]] mrpt::serialization::CArchive& out) const
223  {
224  }
225 
227  virtual void derivedSerializeFrom(
228  [[maybe_unused]] mrpt::serialization::CArchive& in)
229  {
230  }
231 };
232 
246 const mrpt::maps::CPointsMap* MapToPointsMap(const mrpt::maps::CMetricMap& map);
247 
249 mrpt::maps::CPointsMap* MapToPointsMap(mrpt::maps::CMetricMap& map);
250 
256 const mrpt::maps::NearestNeighborsCapable* MapToNN(
257  const mrpt::maps::CMetricMap& map, bool throwIfNotImplemented);
258 
261 } // namespace mp2p_icp
mp2p_icp
Definition: covariance.h:17
mp2p_icp::metric_map_t::empty
virtual bool empty() const
Definition: metricmap.cpp:366
mp2p_icp::metric_map_t::Georeferencing::geo_coord
mrpt::topography::TGeodeticCoords geo_coord
Definition: metricmap.h:102
mp2p_icp::metric_map_t::get_visualization_map_layer
static void get_visualization_map_layer(mrpt::opengl::CSetOfObjects &o, const render_params_point_layer_t &p, const mrpt::maps::CMetricMap::Ptr &map)
Definition: metricmap.cpp:215
mp2p_icp::render_params_point_layer_t
Definition: render_params.h:124
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
render_params.h
Render parameters for the different geometric entities.
mp2p_icp::metric_map_t::PT_LAYER_PLANE_CENTROIDS
constexpr static const char * PT_LAYER_PLANE_CENTROIDS
Definition: metricmap.h:58
mp2p_icp::metric_map_t::save_to_file
bool save_to_file(const std::string &fileName) const
Definition: metricmap.cpp:571
mp2p_icp::metric_map_t::get_visualization_points
void get_visualization_points(mrpt::opengl::CSetOfObjects &o, const render_params_points_t &p) const
Definition: metricmap.cpp:181
mp2p_icp::metric_map_t::derivedSerializeTo
virtual void derivedSerializeTo([[maybe_unused]] mrpt::serialization::CArchive &out) const
Definition: metricmap.h:221
mp2p_icp::metric_map_t::clear
virtual void clear()
Definition: metricmap.cpp:370
mrpt
Definition: LogRecord.h:100
plane_patch.h
Defines plane_patch_t.
mp2p_icp::render_params_planes_t
Definition: render_params.h:32
mp2p_icp::metric_map_t::PT_LAYER_RAW
constexpr static const char * PT_LAYER_RAW
Definition: metricmap.h:57
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::metric_map_t::label
std::optional< std::string > label
Definition: metricmap.h:96
layer_name_t.h
kitti-batch-convert.out
string out
Definition: kitti-batch-convert.py:7
mp2p_icp::metric_map_t::derivedSerializeFrom
virtual void derivedSerializeFrom([[maybe_unused]] mrpt::serialization::CArchive &in)
Definition: metricmap.h:227
mp2p_icp::render_params_lines_t
Definition: render_params.h:53
mp2p_icp::metric_map_t::planes
std::vector< plane_patch_t > planes
Definition: metricmap.h:81
mp2p_icp::MapToPointsMap
const mrpt::maps::CPointsMap * MapToPointsMap(const mrpt::maps::CMetricMap &map)
Definition: metricmap.cpp:652
mp2p_icp::metric_map_t::lines
std::vector< mrpt::math::TLine3D > lines
Definition: metricmap.h:78
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:633
mp2p_icp::metric_map_t::merge_with
virtual void merge_with(const metric_map_t &otherPc, const std::optional< mrpt::math::TPose3D > &otherRelativePose=std::nullopt)
Definition: metricmap.cpp:374
mp2p_icp::metric_map_t::contents_summary
virtual std::string contents_summary() const
Definition: metricmap.cpp:504
mp2p_icp::render_params_t
Definition: render_params.h:184
mp2p_icp::metric_map_t::size
virtual size_t size() const
Definition: metricmap.cpp:479
mp2p_icp::metric_map_t::Georeferencing
Definition: metricmap.h:98
mp2p_icp::metric_map_t::get_visualization
virtual auto get_visualization(const render_params_t &p=render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
Definition: metricmap.cpp:125
mp2p_icp::metric_map_t::get_visualization_lines
void get_visualization_lines(mrpt::opengl::CSetOfObjects &o, const render_params_lines_t &p) const
Definition: metricmap.cpp:161
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:582
mp2p_icp::metric_map_t::Georeferencing::T_enu_to_map
mrpt::poses::CPose3DPDFGaussian T_enu_to_map
Definition: metricmap.h:111
std
mp2p_icp::render_params_points_t
Definition: render_params.h:156
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:48
mp2p_icp::metric_map_t::get_visualization_planes
void get_visualization_planes(mrpt::opengl::CSetOfObjects &o, const render_params_planes_t &p) const
Definition: metricmap.cpp:139
mp2p_icp::metric_map_t::id
std::optional< uint64_t > id
Definition: metricmap.h:88
mp2p_icp::metric_map_t::georeferencing
std::optional< Georeferencing > georeferencing
Definition: metricmap.h:116
mp2p_icp::metric_map_t::get_shared_from_this
Ptr get_shared_from_this()
Definition: metricmap.cpp:593
mp2p_icp::metric_map_t::size_points_only
virtual size_t size_points_only() const
Definition: metricmap.cpp:489
mp2p_icp::metric_map_t::get_shared_from_this_or_clone
Ptr get_shared_from_this_or_clone()
Definition: metricmap.cpp:606
mp2p_icp::MapToNN
const mrpt::maps::NearestNeighborsCapable * MapToNN(const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
Definition: metricmap.cpp:690
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:75


mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Wed Jun 26 2024 02:47:09