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