Class SparseVoxelPointCloud
Defined in File SparseVoxelPointCloud.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Types
public mrpt::maps::CMetricMap
public mrpt::maps::NearestNeighborsCapable
Class Documentation
-
class SparseVoxelPointCloud : public mrpt::maps::CMetricMap, public mrpt::maps::NearestNeighborsCapable
SparseVoxelPointCloud: a pointcloud stored as a sparse-dense set of cubic voxel maps. Efficient for storing point clouds, decimating them, and running nearest nearest-neighbor search.
Compile-time parameters
-
using inner_plain_index_t = uint32_t
-
using global_plain_index_t = uint64_t
collapsed plain unique ID for global indices
-
static constexpr std::size_t HARDLIMIT_MAX_POINTS_PER_VOXEL = 16
Size of the std::array for the small-size optimization container in each voxel, defining the maximum number of points that can be stored without heap allocation.
-
static constexpr uint32_t INNER_GRID_BIT_COUNT = 5
-
static constexpr std::size_t GLOBAL_ID_SUBVOXEL_BITCOUNT = 4
-
static constexpr uint32_t INNER_GRID_SIDE = 1 << INNER_GRID_BIT_COUNT
-
static constexpr uint32_t INNER_COORDS_MASK = INNER_GRID_SIDE - 1
-
static constexpr uint32_t OUTER_COORDS_MASK = ~INNER_COORDS_MASK
Data structures
-
using grids_map_t = std::map<outer_index3d_t, InnerGrid, index3d_hash<int32_t>>
Indices and coordinates
-
static inline outer_index3d_t g2o(const global_index3d_t &g)
-
static inline inner_index3d_t g2i(const global_index3d_t &g)
-
static inline inner_index3d_t plain2i(const inner_plain_index_t &p)
-
static inline global_plain_index_t g2plain(const global_index3d_t &g, int subVoxelIndex = 0)
-
inline global_index3d_t coordToGlobalIdx(const mrpt::math::TPoint3Df &pt) const
-
inline mrpt::math::TPoint3Df globalIdxToCoord(const global_index3d_t idx) const
returns the coordinate of the voxel center
Basic API for construction and main parameters
-
SparseVoxelPointCloud(float voxel_size = 0.20f)
Constructor / default ctor.
- Parameters:
voxel_size – Voxel size [meters] for decimation purposes.
-
~SparseVoxelPointCloud()
-
void setVoxelProperties(float voxel_size)
Reset the main voxel parameters, and clears all current map contents
Data access API
-
inline std::tuple<VoxelData*, InnerGrid*> voxelByGlobalIdxs(const global_index3d_t &idx, bool createIfNew)
returns the voxeldata by global index coordinates, creating it or not if not found depending on createIfNew. Returns nullptr if not found and createIfNew is false
Function defined in the header file so compilers can optimize for literals “createIfNew”
-
inline std::tuple<const VoxelData*, const InnerGrid*> voxelByGlobalIdxs(const global_index3d_t &idx, bool createIfNew) const
-
inline std::tuple<VoxelData&, InnerGrid&> voxelByCoords(const mrpt::math::TPoint3Df &pt)
Get a voxeldata by (x,y,z) coordinates, creating the container grid if needed.
-
inline std::tuple<const VoxelData&, const InnerGrid&> voxelByCoords(const mrpt::math::TPoint3Df &pt) const
-
void insertPoint(const mrpt::math::TPoint3Df &pt)
Insert one point into the dual voxel map
-
inline const grids_map_t &grids() const
-
mrpt::math::TBoundingBoxf boundingBox() const override
Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points. Results are cached unless the map is somehow modified to avoid repeated calculations.
-
void visitAllPoints(const std::function<void(const mrpt::math::TPoint3Df&)> &f) const
-
void visitAllVoxels(const std::function<void(const outer_index3d_t&, const inner_plain_index_t, const VoxelData&, const InnerGrid&)> &f) const
-
void visitAllGrids(const std::function<void(const outer_index3d_t&, const InnerGrid&)> &f) const
-
bool saveToTextFile(const std::string &file) const
Save to a text file. Each line contains “X Y Z” point coordinates. Returns false if any error occured, true elsewere.
API of the NearestNeighborsCapable virtual interface
-
bool nn_has_indices_or_ids() const override
-
size_t nn_index_count() const override
-
bool nn_single_search(const mrpt::math::TPoint3Df &query, mrpt::math::TPoint3Df &result, float &out_dist_sqr, uint64_t &resultIndexOrID) const override
-
bool nn_single_search(const mrpt::math::TPoint2Df &query, mrpt::math::TPoint2Df &result, float &out_dist_sqr, uint64_t &resultIndexOrID) const override
-
void nn_multiple_search(const mrpt::math::TPoint3Df &query, const size_t N, std::vector<mrpt::math::TPoint3Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs) const override
-
void nn_multiple_search(const mrpt::math::TPoint2Df &query, const size_t N, std::vector<mrpt::math::TPoint2Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs) const override
-
void nn_radius_search(const mrpt::math::TPoint3Df &query, const float search_radius_sqr, std::vector<mrpt::math::TPoint3Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs, size_t maxPoints) const override
-
void nn_radius_search(const mrpt::math::TPoint2Df &query, const float search_radius_sqr, std::vector<mrpt::math::TPoint2Df> &results, std::vector<float> &out_dists_sqr, std::vector<uint64_t> &resultIndicesOrIDs, size_t maxPoints) const override
Public virtual methods implementation for CMetricMap
-
std::string asString() const override
Returns a short description of the map.
-
void getVisualizationInto(mrpt::opengl::CSetOfObjects &outObj) const override
-
bool isEmpty() const override
Returns true if the map is empty
-
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file “filNamePrefix”+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).
Public Members
-
TInsertionOptions insertionOptions
-
TLikelihoodOptions likelihoodOptions
-
TRenderOptions renderOptions
-
float voxel_size = 0.20f
-
mola::SparseVoxelPointCloud::TInsertionOptions insertionOpts
-
mola::SparseVoxelPointCloud::TLikelihoodOptions likelihoodOpts
-
mola::SparseVoxelPointCloud::TRenderOptions renderOpts
Protected Functions
-
void internal_clear() override
-
struct InnerGrid
Public Members
-
FixedDenseGrid3D<VoxelData, INNER_GRID_BIT_COUNT, uint32_t> gridData
-
mrpt::maps::CSimplePointsMap points
-
FixedDenseGrid3D<VoxelData, INNER_GRID_BIT_COUNT, uint32_t> gridData
-
struct TInsertionOptions : public mrpt::config::CLoadableOptions
Options for insertObservation()
Public Functions
-
TInsertionOptions() = default
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
void dumpToTextStream(std::ostream &out) const override
-
void writeToStream(mrpt::serialization::CArchive &out) const
-
void readFromStream(mrpt::serialization::CArchive &in)
Public Members
-
uint32_t max_points_per_voxel = 0
Maximum number of points per voxel. 0 means no limit (up to the compile-time limit HARDLIMIT_MAX_POINTS_PER_VOXEL).
-
TInsertionOptions() = default
-
struct TLikelihoodOptions : public mrpt::config::CLoadableOptions
Options used when evaluating “computeObservationLikelihood” in the derived classes.
See also
CObservation::computeObservationLikelihood
Public Functions
-
TLikelihoodOptions() = default
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
void dumpToTextStream(std::ostream &out) const override
-
void writeToStream(mrpt::serialization::CArchive &out) const
-
void readFromStream(mrpt::serialization::CArchive &in)
Public Members
-
double sigma_dist = 0.5
Sigma (standard deviation, in meters) of the Gaussian observation model used to model the likelihood (default= 0.5 m)
-
double max_corr_distance = 1.0
Maximum distance in meters to consider for the numerator divided by “sigma_dist”, so that each point has a minimum (but very small) likelihood to avoid underflows (default=1.0 meters)
-
uint32_t decimation = 10
Speed up the likelihood computation by considering only one out of N rays (default=10)
-
bool match_mean = false
If true, search for pairings only against the voxel mean point, instead of the contained points.
This parameters affects both, likelihood, and the NN (nearest-neighbors) API methods.
-
TLikelihoodOptions() = default
-
struct TRenderOptions : public mrpt::config::CLoadableOptions
Rendering options, used in getAs3DObject()
Public Functions
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
void dumpToTextStream(std::ostream &out) const override
-
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - used in derived classes’ serialization
-
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - used in derived classes’ serialization
Public Members
-
float point_size = 1.0f
-
bool show_mean_only = true
If true, when rendering a voxel map only the mean point per voxel will be rendered instead of all contained points.
-
bool show_inner_grid_boxes = false
-
mrpt::img::TColorf color = {.0f, .0f, 1.0f}
Color of points. Superseded by colormap if the latter is set.
-
mrpt::img::TColormap colormap = mrpt::img::cmHOT
Colormap for points (index is “z” coordinates)
-
uint8_t recolorizeByCoordinateIndex = 2
If colormap!=mrpt::img::cmNONE, use this coordinate as color index: 0=x 1=y 2=z
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
struct VoxelData
Public Functions
-
VoxelData() = default
-
inline const mrpt::math::TPoint3Df &mean() const
Gets the mean of all points in the voxel. Throws if empty.
-
inline size_t size() const
-
inline void resize(size_t n)
-
inline void setIndex(size_t i, uint32_t idx)
-
inline uint32_t getIndex(size_t i) const
-
struct PointSpan
-
VoxelData() = default
-
using inner_plain_index_t = uint32_t