VoxelGrid.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <filesystem>
4 #include <set>
5 
6 #include <SimoxUtility/json/json.hpp>
7 
9 
10 #include "../types.h"
11 #include "../LabelDensity/VoxelGrid.h"
12 
13 
15 {
16 
17  // VOXEL TYPE
18 
19  /**
20  * @brief A voxel storing whether it is occupied or free and the object
21  * label it is occupied by.
22  */
23  class Voxel
24  {
25  public:
26 
27  /// Construct an unoccupied voxel.
28  Voxel();
29  /// Construct an occupied voxel with given label.
30  Voxel(Label label);
31 
32  /// Indicate whether this voxel is free (i.e. it is not occupied).
33  bool isFree() const;
34  /// Indicate whether this voxel is occupied.
35  bool isOccupied() const;
36 
37  /// Get the label. Voxel must be occupied.
38  Label getLabel() const;
39 
40  /// Set the voxel to free, i.e. unoccupied.
41  void setFree();
42  /// Set the voxel to occupied and set its label.
43  void setOccupied(Label label);
44 
45 
46  private:
47 
48  /// Whether this voxel is occupied.
49  bool _isOccupied = true;
50  /// If occupied, the object label occupying this object.
51  Label _label = 0;
52 
53  };
54 
55 
56  /// Set `json` to the voxel's label if occupied, and to -1 if free.
57  void to_json(nlohmann::json& json, const Voxel& voxel);
58  /// Set this voxel free, if `json` is < 0.
59  /// Otherwise, set `voxel`'s label to `json`.
60  void from_json(const nlohmann::json& json, 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  /**
76  * @brief Make a label occupancy grid from the given density grid.
77  * @see `setByLabelDensity()`
78  */
79  static VoxelGrid fromLabelDensity(const LabelDensity::VoxelGrid& density);
80 
81 
82  using Base::VoxelGrid;
83 
84 
85  /// Get the set of unique labels in the grid.
86  std::set<Label> getUniqueLabels() const;
87 
88 
89 
90  /**
91  * @brief Set the voxels by selecting the label with most points
92  * for each voxel.
93  *
94  * This overwrites any information previously stored in this grid.
95  *
96  * @param density The label density grid.
97  * @param adoptStructure
98  * If false, throws an exception if `density`'s structure is not
99  * equal to the structure of `*this`. If you wish to adopt
100  * `density`s structure, pass true.
101  *
102  * @throw `voxelgrid::error::InvalidStructure`
103  * If `density`'s structure is different to `getStructure()`
104  * and `adoptStructure` is false.
105  */
106  void setByLabelDensity(const LabelDensity::VoxelGrid& density,
107  bool adoptStructure = false);
108 
109 
110  // Serialization
111 
112  /// Write this voxel grid to JSON.
113  void writeJson(std::ostream& os) const;
114  void writeJson(const std::filesystem::path& file) const;
115 
116  /// Read this voxel grid from JSON.
117  void readJson(std::istream& is);
118  void readJson(const std::filesystem::path& file);
119 
120 
121  public:
122 
123  /// Name of the single voxel array in JSON.
124  static const std::string JSON_VOXEL_ARRAY_NAME;
125 
126  };
127 
128 
129  /// Write the voxel grid to JSON.
130  void to_json(nlohmann::json& json, const VoxelGrid& grid);
131  /// Read the voxel grid from JSON.
132  void from_json(const nlohmann::json& json, VoxelGrid& grid);
133 
134 }
visionx::voxelgrid::LabelOccupancy::to_json
void to_json(nlohmann::json &json, const Voxel &voxel)
Set json to the voxel's label if occupied, and to -1 if free.
Definition: VoxelGrid.cpp:52
visionx::voxelgrid::LabelOccupancy::Voxel::isFree
bool isFree() const
Indicate whether this voxel is free (i.e. it is not occupied).
Definition: VoxelGrid.cpp:23
visionx::voxelgrid::VoxelGrid< VoxelT >
visionx::voxelgrid::LabelOccupancy::Voxel::setFree
void setFree()
Set the voxel to free, i.e. unoccupied.
Definition: VoxelGrid.cpp:39
visionx::voxelgrid::LabelOccupancy::VoxelGrid::writeJson
void writeJson(std::ostream &os) const
Write this voxel grid to JSON.
Definition: VoxelGrid.cpp:132
visionx::voxelgrid::LabelOccupancy::VoxelGrid::getUniqueLabels
std::set< Label > getUniqueLabels() const
Get the set of unique labels in the grid.
Definition: VoxelGrid.cpp:87
visionx::voxelgrid::LabelOccupancy
Definition: Visualizer.cpp:9
visionx::voxelgrid::LabelOccupancy::VoxelGrid
Voxel grid storing the number of points per label in each voxel.
Definition: VoxelGrid.h:69
visionx::voxelgrid::LabelDensity::VoxelGrid
Voxel grid storing the number of points per label in each voxel.
Definition: VoxelGrid.h:69
visionx::voxelgrid::Label
uint32_t Label
Type of an object label.
Definition: types.h:7
visionx::voxelgrid::LabelOccupancy::Voxel::isOccupied
bool isOccupied() const
Indicate whether this voxel is occupied.
Definition: VoxelGrid.cpp:28
visionx::voxelgrid::LabelOccupancy::from_json
void from_json(const nlohmann::json &json, Voxel &voxel)
Set this voxel free, if json is < 0.
Definition: VoxelGrid.cpp:64
visionx::voxelgrid::LabelOccupancy::Voxel::setOccupied
void setOccupied(Label label)
Set the voxel to occupied and set its label.
Definition: VoxelGrid.cpp:45
VoxelGridCore.h
visionx::voxelgrid::LabelOccupancy::VoxelGrid::JSON_VOXEL_ARRAY_NAME
static const std::string JSON_VOXEL_ARRAY_NAME
Name of the single voxel array in JSON.
Definition: VoxelGrid.h:124
visionx::voxelgrid::LabelOccupancy::Voxel::Voxel
Voxel()
Construct an unoccupied voxel.
Definition: VoxelGrid.cpp:13
visionx::voxelgrid::LabelOccupancy::VoxelGrid::fromLabelDensity
static VoxelGrid fromLabelDensity(const LabelDensity::VoxelGrid &density)
Make a label occupancy grid from the given density grid.
Definition: VoxelGrid.cpp:80
visionx::voxelgrid::LabelOccupancy::VoxelGrid::readJson
void readJson(std::istream &is)
Read this voxel grid from JSON.
Definition: VoxelGrid.cpp:142
visionx::VoxelGrid
voxelgrid::VoxelGrid< VoxelT > VoxelGrid
Definition: VoxelGridCore.h:33
visionx::voxelgrid::LabelOccupancy::Voxel
A voxel storing whether it is occupied or free and the object label it is occupied by.
Definition: VoxelGrid.h:23
visionx::voxelgrid::LabelOccupancy::Voxel::getLabel
Label getLabel() const
Get the label. Voxel must be occupied.
Definition: VoxelGrid.cpp:33
visionx::voxelgrid::LabelOccupancy::VoxelGrid::setByLabelDensity
void setByLabelDensity(const LabelDensity::VoxelGrid &density, bool adoptStructure=false)
Set the voxels by selecting the label with most points for each voxel.
Definition: VoxelGrid.cpp:100