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-2021 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/math/TLine3D.h>
19 #include <mrpt/math/TPoint3D.h>
20 #include <mrpt/math/geometry.h>
21 #include <mrpt/serialization/CSerializable.h>
22 
23 #include <map>
24 #include <memory>
25 #include <optional>
26 #include <string>
27 #include <vector>
28 
29 namespace mp2p_icp
30 {
47 class metric_map_t : public mrpt::serialization::CSerializable,
48  public std::enable_shared_from_this<metric_map_t>
49 {
50  DEFINE_SERIALIZABLE(metric_map_t, mp2p_icp)
51 
52  public:
56  constexpr static const char* PT_LAYER_RAW = "raw";
57  constexpr static const char* PT_LAYER_PLANE_CENTROIDS = "plane_centroids";
58 
74  std::map<layer_name_t, mrpt::maps::CMetricMap::Ptr> layers;
75 
77  std::vector<mrpt::math::TLine3D> lines;
78 
80  std::vector<plane_patch_t> planes;
81 
87  std::optional<uint64_t> id;
88 
95  std::optional<std::string> label;
96 
103  virtual bool empty() const;
104 
106  virtual size_t size() const;
107 
109  virtual size_t size_points_only() const;
110 
113  virtual std::string contents_summary() const;
114 
116  virtual void clear();
117 
122  bool save_to_file(const std::string& fileName) const;
123 
127  bool load_from_file(const std::string& fileName);
128 
138  mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t& name) const;
139 
149  virtual auto get_visualization(const render_params_t& p = render_params_t())
150  const -> std::shared_ptr<mrpt::opengl::CSetOfObjects>;
151 
160  virtual void merge_with(
161  const metric_map_t& otherPc,
162  const std::optional<mrpt::math::TPose3D>& otherRelativePose =
163  std::nullopt);
164 
167  mrpt::opengl::CSetOfObjects& o, const render_params_planes_t& p) const;
168 
171  mrpt::opengl::CSetOfObjects& o, const render_params_lines_t& p) const;
172 
175  mrpt::opengl::CSetOfObjects& o, const render_params_points_t& p) const;
176 
178  static void get_visualization_point_layer(
179  mrpt::opengl::CSetOfObjects& o, const render_params_point_layer_t& p,
180  const mrpt::maps::CPointsMap::Ptr& pts);
181 
185  Ptr get_shared_from_this();
186 
191 
192  // const versions:
193  ConstPtr get_shared_from_this() const;
194  ConstPtr get_shared_from_this_or_clone() const;
195 
198  protected:
200  virtual void derivedSerializeTo([
201  [maybe_unused]] mrpt::serialization::CArchive& out) const
202  {
203  }
204 
206  virtual void derivedSerializeFrom([
207  [maybe_unused]] mrpt::serialization::CArchive& in)
208  {
209  }
210 };
211 
217 {
218  pointcloud_bitfield_t() = default;
219  ~pointcloud_bitfield_t() = default;
220 
223  std::map<layer_name_t, std::vector<bool>> point_layers;
224  std::vector<bool> lines;
225  std::vector<bool> planes;
228  void initialize_from(const metric_map_t& pc, bool initBoolValue = false)
229  {
230  // Points:
231  // Done in this way to avoid avoidable memory reallocations.
232  for (const auto& kv : pc.layers)
233  {
234  ASSERT_(kv.second);
235  auto pts =
236  std::dynamic_pointer_cast<mrpt::maps::CPointsMap>(kv.second);
237  if (!pts) continue;
238  point_layers[kv.first].assign(pts->size(), initBoolValue);
239  }
240  std::set<layer_name_t> layersToRemove;
241  for (auto& kv : point_layers)
242  {
243  if (pc.layers.count(kv.first) == 0) layersToRemove.insert(kv.first);
244  }
245  for (const auto& ly : layersToRemove) point_layers.erase(ly);
246 
247  // Lines:
248  lines.assign(pc.lines.size(), initBoolValue);
249 
250  // planes:
251  planes.assign(pc.planes.size(), initBoolValue);
252  }
253 };
254 
257 } // namespace mp2p_icp
mp2p_icp::pointcloud_bitfield_t::lines
std::vector< bool > lines
Definition: metricmap.h:224
mp2p_icp
Definition: covariance.h:17
mp2p_icp::metric_map_t::empty
virtual bool empty() const
Definition: metricmap.cpp:245
mp2p_icp::render_params_point_layer_t
Definition: render_params.h:80
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:57
mp2p_icp::metric_map_t::save_to_file
bool save_to_file(const std::string &fileName) const
Definition: metricmap.cpp:421
mp2p_icp::pointcloud_bitfield_t::planes
std::vector< bool > planes
Definition: metricmap.h:225
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:152
mp2p_icp::pointcloud_bitfield_t::initialize_from
void initialize_from(const metric_map_t &pc, bool initBoolValue=false)
Definition: metricmap.h:228
mp2p_icp::layer_name_t
std::string layer_name_t
Definition: layer_name_t.h:22
mp2p_icp::metric_map_t::derivedSerializeTo
virtual void derivedSerializeTo([[maybe_unused]] mrpt::serialization::CArchive &out) const
Definition: metricmap.h:200
mp2p_icp::metric_map_t::clear
virtual void clear()
Definition: metricmap.cpp:249
mrpt
Definition: LogRecord.h:99
plane_patch.h
Defines plane_patch_t.
mp2p_icp::metric_map_t::get_visualization_point_layer
static void get_visualization_point_layer(mrpt::opengl::CSetOfObjects &o, const render_params_point_layer_t &p, const mrpt::maps::CPointsMap::Ptr &pts)
Definition: metricmap.cpp:193
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:56
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::metric_map_t::label
std::optional< std::string > label
Definition: metricmap.h:95
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:206
mp2p_icp::pointcloud_bitfield_t::point_layers
std::map< layer_name_t, std::vector< bool > > point_layers
Definition: metricmap.h:223
mp2p_icp::render_params_lines_t
Definition: render_params.h:43
mp2p_icp::metric_map_t::planes
std::vector< plane_patch_t > planes
Definition: metricmap.h:80
mp2p_icp::metric_map_t::lines
std::vector< mrpt::math::TLine3D > lines
Definition: metricmap.h:77
mp2p_icp::metric_map_t::point_layer
mrpt::maps::CPointsMap::Ptr point_layer(const layer_name_t &name) const
Definition: metricmap.cpp:483
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:252
mp2p_icp::metric_map_t::contents_summary
virtual std::string contents_summary() const
Definition: metricmap.cpp:375
mp2p_icp::render_params_t
Definition: render_params.h:115
mp2p_icp::metric_map_t::size
virtual size_t size() const
Definition: metricmap.cpp:352
mp2p_icp::pointcloud_bitfield_t::pointcloud_bitfield_t
pointcloud_bitfield_t()=default
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:96
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:132
mp2p_icp::metric_map_t::load_from_file
bool load_from_file(const std::string &fileName)
Definition: metricmap.cpp:432
std
mp2p_icp::render_params_points_t
Definition: render_params.h:97
mp2p_icp::metric_map_t
Generic container of pointcloud(s), extracted features and other maps.
Definition: metricmap.h:47
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:110
mp2p_icp::metric_map_t::id
std::optional< uint64_t > id
Definition: metricmap.h:87
mp2p_icp::metric_map_t::get_shared_from_this
Ptr get_shared_from_this()
Definition: metricmap.cpp:443
mp2p_icp::metric_map_t::size_points_only
virtual size_t size_points_only() const
Definition: metricmap.cpp:362
mp2p_icp::metric_map_t::get_shared_from_this_or_clone
Ptr get_shared_from_this_or_clone()
Definition: metricmap.cpp:456
mp2p_icp::pointcloud_bitfield_t::~pointcloud_bitfield_t
~pointcloud_bitfield_t()=default
mp2p_icp::pointcloud_bitfield_t
Definition: metricmap.h:216
mp2p_icp::metric_map_t::layers
std::map< layer_name_t, mrpt::maps::CMetricMap::Ptr > layers
Definition: metricmap.h:74


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