Go to the documentation of this file.
9 #include <pcl/point_cloud.h>
10 #include <pcl/point_types.h>
12 #include <SimoxUtility/json/json.hpp>
27 class Voxel :
public std::map<Label, std::size_t>
29 using Base = std::map<Label, std::size_t>;
51 std::pair<Label, std::size_t>
getMax()
const;
83 void addPointCloud(
const pcl::PointCloud<pcl::PointXYZL>& pointCloud,
85 void addPointCloud(
const pcl::PointCloud<pcl::PointXYZRGBL>& pointCloud,
101 void writeJson(
const std::filesystem::path& file)
const;
105 void readJson(
const std::filesystem::path& file);
119 void toCsv(std::ostream& os,
bool includeTotal =
false)
const;
120 void toCsv(
const std::filesystem::path& file,
bool includeTotal =
false)
const;
Label getMaxLabel() const
Get the label with most points.
void toCsv(std::ostream &os, bool includeTotal=false) const
Write the voxel data to a CSV file.
void reduceNoise(std::size_t minNumPoints)
Remove entries with number of points below minNumPoints.
Voxel grid storing the number of points per label in each voxel.
void readJson(std::istream &is)
Read this voxel grid from JSON.
void writeJson(std::ostream &os) const
Write this voxel grid to JSON.
bool isFree() const
Indicate whether this voxel is free, i.e. it contains no points.
uint32_t Label
Type of an object label.
void Identity(MatrixXX< N, N, T > *a)
friend std::ostream & operator<<(std::ostream &os, const Voxel &voxel)
Outstream operator.
std::map< Label, float > getDensity() const
Get the relative frequency of labels, so that the sum is 1.0.
std::size_t getTotal() const
Get the total number of points in this voxel.
std::pair< Label, std::size_t > getMax() const
Get the label with most points and the number of points.
Map of labels (object IDs) to number of points.
std::set< Label > getUniqueLabels() const
Get the set of unique labels.
void addPointCloud(const pcl::PointCloud< pcl::PointXYZL > &pointCloud, const Eigen::Matrix4f &pointCloudPose=Eigen::Matrix4f::Identity())
Add the point cloud.
void from_json(const nlohmann::json &json, VoxelGrid &grid)
Read the voxel grid from JSON.
MatrixXX< 4, 4, float > Matrix4f
bool operator==(const Voxel &rhs) const
Equality operator.
voxelgrid::VoxelGrid< VoxelT > VoxelGrid
void to_json(nlohmann::json &json, const VoxelGrid &grid)
Write the voxel grid to JSON.
bool operator!=(const Voxel &rhs) const