Go to the documentation of this file.
20 #ifndef VOXEL_GRID__VOXEL_HPP_
21 #define VOXEL_GRID__VOXEL_HPP_
41 template<
typename Po
intT>
52 explicit Voxel(
const PointT & pt)
59 explicit operator bool()
const
66 explicit operator PointT()
const
87 const PointT &
get()
const
90 throw std::out_of_range(
"Voxel: Cannot get point from an unoccupied voxel");
121 uint32_t m_num_points;
129 #endif // VOXEL_GRID__VOXEL_HPP_
bool occupied() const
Whether or not this object has at least one point associated with it.
Definition: voxel.hpp:73
void set_centroid(const PointT &pt)
Sets the centroid. This is to properly encapsulate the member variables. Intended to be used by child...
Definition: voxel.hpp:114
uint32_t count() const
Get the current number of points associated with this voxel.
Definition: voxel.hpp:97
Voxel()
Default constructor, corresponds to an empty/uninitialized voxel.
Definition: voxel.hpp:47
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
const PointT & get() const
Emit the centroid.
Definition: voxel.hpp:87
void clear()
Resets the centroid for incremental updating.
Definition: voxel.hpp:79
void set_count(const uint32_t next)
Sets the count. This is to properly encapsulate the member variables. Intended to be used by child cl...
Definition: voxel.hpp:106
Voxel(const PointT &pt)
Point constructor, voxel is assumed to be created based on this point.
Definition: voxel.hpp:52
A simple class to accumulate points for a voxel and emit the centroid.
Definition: voxel.hpp:42
PointT point_t
Definition: voxel.hpp:45