VoxelGrid.cpp
Go to the documentation of this file.
1 #include "VoxelGrid.h"
2 
3 #include "../utils.h"
4 
6 
7 #include <algorithm>
8 
9 
11 {
12 
14  {
15  setFree();
16  }
17 
19  {
20  setOccupied(label);
21  }
22 
23  bool Voxel::isFree() const
24  {
25  return !isOccupied();
26  }
27 
28  bool Voxel::isOccupied() const
29  {
30  return _isOccupied;
31  }
32 
34  {
36  return _label;
37  }
38 
40  {
41  _isOccupied = false;
42  _label = 0;
43  }
44 
46  {
47  _isOccupied = true;
48  this->_label = label;
49  }
50 
51 
52  void to_json(nlohmann::json& json, const Voxel& voxel)
53  {
54  if (voxel.isOccupied())
55  {
56  json = voxel.getLabel();
57  }
58  else
59  {
60  json = -1;
61  }
62  }
63 
64  void from_json(const nlohmann::json& json, Voxel& voxel)
65  {
66  if (json.get<int>() < 0)
67  {
68  voxel.setFree();
69  }
70  else
71  {
72  voxel.setOccupied(json.get<Label>());
73  }
74  }
75 
76 
77  const std::string VoxelGrid::JSON_VOXEL_ARRAY_NAME = "labels";
78 
79 
81  {
82  VoxelGrid grid(density.getStructure());
83  grid.setByLabelDensity(density);
84  return grid;
85  }
86 
87  std::set<Label> VoxelGrid::getUniqueLabels() const
88  {
89  std::set<Label> ids;
90  for (const Voxel& voxel : *this)
91  {
92  if (voxel.isOccupied())
93  {
94  ids.insert(voxel.getLabel());
95  }
96  }
97  return ids;
98  }
99 
101  const LabelDensity::VoxelGrid& density, bool adoptStructure)
102  {
103  if (density.getStructure() != getStructure())
104  {
105  if (adoptStructure)
106  {
107  resetStructure(density.getStructure());
108  }
109  else
110  {
112  density.getStructure(), getStructure(),
113  "Provided density grid has different structure, but adoptStructure is false.");
114  }
115  }
116 
117  for (std::size_t i = 0; i < numVoxels(); ++i)
118  {
119  const LabelDensity::Voxel& voxel = density.getVoxel(i);
120  if (voxel.isFree())
121  {
122  getVoxel(i).setFree();
123  }
124  else
125  {
126  getVoxel(i).setOccupied(voxel.getMaxLabel());
127  }
128  }
129  }
130 
131 
132  void VoxelGrid::writeJson(std::ostream& os) const
133  {
135  }
136 
137  void VoxelGrid::writeJson(const std::filesystem::path& file) const
138  {
140  }
141 
142  void VoxelGrid::readJson(std::istream& is)
143  {
145  }
146 
147  void VoxelGrid::readJson(const std::filesystem::path& file)
148  {
150  }
151 
152 
153  void to_json(nlohmann::json& json, const VoxelGrid& grid)
154  {
156  }
157 
158  void from_json(const nlohmann::json& json, VoxelGrid& grid)
159  {
161  }
162 
163 }
visionx::voxelgrid::io::JsonIO::fromJson
static void fromJson(const nlohmann::json &j, VoxelGrid< VoxelT > &grid, const VoxelAttributeSetterMap< VoxelT > &attributeMap)
Deserialize a voxel grid from JSON.
Definition: JsonIO.h:306
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::io::JsonIO::toJson
static void toJson(nlohmann::json &j, const VoxelGrid< VoxelT > &grid, const VoxelAttributeGetterMap< VoxelT > &attributeMap)
Serialize a voxel grid to JSON.
Definition: JsonIO.h:259
visionx::voxelgrid::LabelDensity::Voxel::getMaxLabel
Label getMaxLabel() const
Get the label with most points.
Definition: VoxelGrid.cpp:42
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::VoxelGrid< VoxelT >::resetStructure
void resetStructure(const VoxelGridStructure &structure)
Set the voxel grid structure and reset voxel data.
Definition: VoxelGrid.hpp:96
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::io::JsonIO::writeJson
static void writeJson(const std::string &filename, const nlohmann::json &j, int indent=-1, char indentChar=' ')
Write JSON json to file.
Definition: JsonIO.cpp:8
visionx::voxelgrid::VoxelGrid::getStructure
VoxelGridStructure getStructure() const
Get the voxel grid structure.
Definition: VoxelGrid.hpp:91
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
visionx::voxelgrid::VoxelGrid::getVoxel
VoxelT & getVoxel(std::size_t index)
Get the voxel with the given index.
Definition: VoxelGrid.hpp:104
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
visionx::voxelgrid::VoxelGrid< VoxelT >::numVoxels
std::size_t numVoxels() const
Get the number of voxels in the grid.
Definition: VoxelGrid.hpp:165
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
visionx::voxelgrid::io::JsonIO::readJson
static nlohmann::json readJson(const std::string &filename)
Read JSON from file.
Definition: JsonIO.cpp:23
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::LabelDensity::Voxel
Map of labels (object IDs) to number of points.
Definition: VoxelGrid.h:27
visionx::voxelgrid::LabelOccupancy::Voxel::Voxel
Voxel()
Construct an unoccupied voxel.
Definition: VoxelGrid.cpp:13
VoxelGrid.h
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::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::error::InvalidStructure
Indicates that a voxel grid structure should have matched another one, but did not.
Definition: exceptions.h:43
JsonIO.h
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