VoxelGrid.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <filesystem>
4 #include <map>
5 #include <set>
6 
7 #include <Eigen/Core>
8 
9 #include <pcl/point_cloud.h>
10 #include <pcl/point_types.h>
11 
12 #include <SimoxUtility/json/json.hpp>
13 
15 
16 #include "../types.h"
17 
18 
20 {
21 
22  // VOXEL TYPE
23 
24  /**
25  * @brief Map of labels (object IDs) to number of points.
26  */
27  class Voxel : public std::map<Label, std::size_t>
28  {
29  using Base = std::map<Label, std::size_t>;
30 
31  public:
32 
33  using Base::map;
34 
35 
36  /// Indicate whether this voxel is free, i.e. it contains no points.
37  bool isFree() const;
38 
39  /// Get the total number of points in this voxel.
40  std::size_t getTotal() const;
41 
42  /// Get the relative frequency of labels, so that the sum is 1.0.
43  /// If `getTotal()` is 0, the total of the returned density is also 0.0.
44  std::map<Label, float> getDensity() const;
45 
46 
47  /// Get the label with most points.
48  Label getMaxLabel() const;
49 
50  /// Get the label with most points and the number of points.
51  std::pair<Label, std::size_t> getMax() const;
52 
53 
54  /// Equality operator.
55  /// Considers a non-existent label and a label with count 0 equal.
56  bool operator==(const Voxel& rhs) const;
57  bool operator!=(const Voxel& rhs) const;
58 
59  /// Outstream operator.
60  friend std::ostream& operator<<(std::ostream& os, const Voxel& voxel);
61  };
62 
63 
64  // VOXEL GRID
65 
66  /**
67  * @brief Voxel grid storing the number of points per label in each voxel.
68  */
69  class VoxelGrid : public visionx::VoxelGrid<Voxel>
70  {
72 
73  public:
74 
75  using Base::VoxelGrid;
76 
77 
78  /**
79  * @brief Add the point cloud.
80  * @param pointCloud The point cloud.
81  * @param pointCloudPose The point cloud pose (in the same frame as the grid's pose).
82  */
83  void addPointCloud(const pcl::PointCloud<pcl::PointXYZL>& pointCloud,
84  const Eigen::Matrix4f& pointCloudPose = Eigen::Matrix4f::Identity());
85  void addPointCloud(const pcl::PointCloud<pcl::PointXYZRGBL>& pointCloud,
86  const Eigen::Matrix4f& pointCloudPose = Eigen::Matrix4f::Identity());
87 
88 
89  /// Get the set of unique labels.
90  std::set<Label> getUniqueLabels() const;
91 
92 
93  /// Remove entries with number of points below `minNumPoints`.
94  void reduceNoise(std::size_t minNumPoints);
95 
96 
97  // Serialization
98 
99  /// Write this voxel grid to JSON.
100  void writeJson(std::ostream& os) const;
101  void writeJson(const std::filesystem::path& file) const;
102 
103  /// Read this voxel grid from JSON.
104  void readJson(std::istream& is);
105  void readJson(const std::filesystem::path& file);
106 
107 
108  /**
109  * @brief Write the voxel data to a CSV file. (Structure is not stored.)
110  *
111  * The first column, "index", specified the flat voxel index.
112  * The other columns represent the labels, and each row entry
113  * specifies the number of points with that label in the respective
114  * voxel.
115  *
116  * If `includeTotal` is true, a final column "total" is added, storing
117  * the voxel-wise total number of points.
118  */
119  void toCsv(std::ostream& os, bool includeTotal = false) const;
120  void toCsv(const std::filesystem::path& file, bool includeTotal = false) const;
121 
122  };
123 
124 
125  /// Write the voxel grid to JSON.
126  void to_json(nlohmann::json& json, const VoxelGrid& grid);
127  /// Read the voxel grid from JSON.
128  void from_json(const nlohmann::json& json, VoxelGrid& grid);
129 
130 
131 }
visionx::voxelgrid::VoxelGrid< VoxelT >
visionx::voxelgrid::LabelDensity::Voxel::getMaxLabel
Label getMaxLabel() const
Get the label with most points.
Definition: VoxelGrid.cpp:42
visionx::voxelgrid::LabelDensity::VoxelGrid::toCsv
void toCsv(std::ostream &os, bool includeTotal=false) const
Write the voxel data to a CSV file.
Definition: VoxelGrid.cpp:273
visionx::voxelgrid::LabelDensity::VoxelGrid::reduceNoise
void reduceNoise(std::size_t minNumPoints)
Remove entries with number of points below minNumPoints.
Definition: VoxelGrid.cpp:156
visionx::voxelgrid::LabelDensity::VoxelGrid
Voxel grid storing the number of points per label in each voxel.
Definition: VoxelGrid.h:69
visionx::voxelgrid::LabelDensity::VoxelGrid::readJson
void readJson(std::istream &is)
Read this voxel grid from JSON.
Definition: VoxelGrid.cpp:247
visionx::voxelgrid::LabelDensity::VoxelGrid::writeJson
void writeJson(std::ostream &os) const
Write this voxel grid to JSON.
Definition: VoxelGrid.cpp:237
visionx::voxelgrid::LabelDensity::Voxel::isFree
bool isFree() const
Indicate whether this voxel is free, i.e. it contains no points.
Definition: VoxelGrid.cpp:15
visionx::voxelgrid::Label
uint32_t Label
Type of an object label.
Definition: types.h:7
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:523
visionx::voxelgrid::LabelDensity::Voxel::operator<<
friend std::ostream & operator<<(std::ostream &os, const Voxel &voxel)
Outstream operator.
Definition: VoxelGrid.cpp:84
visionx::voxelgrid::LabelDensity::Voxel::getDensity
std::map< Label, float > getDensity() const
Get the relative frequency of labels, so that the sum is 1.0.
Definition: VoxelGrid.cpp:30
visionx::voxelgrid::LabelDensity::Voxel::getTotal
std::size_t getTotal() const
Get the total number of points in this voxel.
Definition: VoxelGrid.cpp:20
visionx::voxelgrid::LabelDensity::Voxel::getMax
std::pair< Label, std::size_t > getMax() const
Get the label with most points and the number of points.
Definition: VoxelGrid.cpp:47
VoxelGridCore.h
visionx::voxelgrid::LabelDensity::Voxel
Map of labels (object IDs) to number of points.
Definition: VoxelGrid.h:27
visionx::voxelgrid::LabelDensity::VoxelGrid::getUniqueLabels
std::set< Label > getUniqueLabels() const
Get the set of unique labels.
Definition: VoxelGrid.cpp:143
visionx::voxelgrid::LabelDensity::VoxelGrid::addPointCloud
void addPointCloud(const pcl::PointCloud< pcl::PointXYZL > &pointCloud, const Eigen::Matrix4f &pointCloudPose=Eigen::Matrix4f::Identity())
Add the point cloud.
Definition: VoxelGrid.cpp:128
visionx::voxelgrid::LabelDensity::from_json
void from_json(const nlohmann::json &json, VoxelGrid &grid)
Read the voxel grid from JSON.
Definition: VoxelGrid.cpp:267
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:601
visionx::voxelgrid::LabelDensity::Voxel::operator==
bool operator==(const Voxel &rhs) const
Equality operator.
Definition: VoxelGrid.cpp:52
visionx::VoxelGrid
voxelgrid::VoxelGrid< VoxelT > VoxelGrid
Definition: VoxelGridCore.h:33
visionx::voxelgrid::LabelDensity::to_json
void to_json(nlohmann::json &json, const VoxelGrid &grid)
Write the voxel grid to JSON.
Definition: VoxelGrid.cpp:262
visionx::voxelgrid::LabelDensity
Definition: Visualizer.cpp:9
visionx::voxelgrid::LabelDensity::Voxel::operator!=
bool operator!=(const Voxel &rhs) const
Definition: VoxelGrid.cpp:79