Class SparseTreesPointCloud

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

  • public mrpt::maps::CMetricMap

  • public mrpt::maps::NearestNeighborsCapable

Class Documentation

class SparseTreesPointCloud : public mrpt::maps::CMetricMap, public mrpt::maps::NearestNeighborsCapable

SparseTreesPointCloud: Point cloud stored as a 3D grid of KD-trees/pointclouds. Efficient for storing point clouds and running nearest nearest-neighbor search.

Compile-time parameters

using outer_index3d_t = index3d_t<int32_t>
using inner_plain_index_t = uint32_t
using global_plain_index_t = uint64_t

collapsed plain unique ID for global indices

static constexpr uint8_t GLOBAL_ID_SUBVOXEL_BITCOUNT = 20

Data structures

using grids_map_t = std::map<outer_index3d_t, GridData, index3d_hash<int32_t>>

Indices and coordinates

inline outer_index3d_t coordToOuterIdx(const mrpt::math::TPoint3Df &pt) const
inline mrpt::math::TPoint3Df outerIdxToCoord(const outer_index3d_t idx) const

returns the coordinate of the voxel center

static inline global_plain_index_t g2plain(const outer_index3d_t &g, int subVoxelIndex = 0)

Basic API for construction and main parameters

SparseTreesPointCloud(float grid_size = 10.0f)

Constructor / default ctor.

Parameters:

voxel_size – Voxel size [meters] for decimation purposes.

~SparseTreesPointCloud()
void setGridProperties(float grid_size)

Reset the main voxel parameters, and clears all current map contents

Data access API

inline GridData *gridByOuterIdxs(const outer_index3d_t &oIdx, 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 const GridData *gridByOuterIdxs(const outer_index3d_t &oIdx, bool createIfNew) const
inline void insertPoint(const mrpt::math::TPoint3Df &pt)

Insert one point into the sparse grid 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 visitAllGrids(const std::function<void(const outer_index3d_t&, const GridData&)> &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.

void eraseGridsFartherThan(const mrpt::math::TPoint3Df &pt, const float distanceMeters)

Erase submap blocks entirely farther away than the given distance threshold.

API of the NearestNeighborsCapable virtual interface

void nn_prepare_for_2d_queries() const override
void nn_prepare_for_3d_queries() const override
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 grid_size = 10.0f
mola::SparseTreesPointCloud::TInsertionOptions insertionOpts
mola::SparseTreesPointCloud::TLikelihoodOptions likelihoodOpts
mola::SparseTreesPointCloud::TRenderOptions renderOpts

Protected Functions

void internal_clear() override
struct GridData

Public Functions

GridData() = default
inline auto &points()
inline const auto &points() const
inline void insertPoint(const mrpt::math::TPoint3Df &p)
struct TInsertionOptions : public mrpt::config::CLoadableOptions

Options for insertObservation()

Public Functions

TInsertionOptions() = default
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
void writeToStream(mrpt::serialization::CArchive &out) const
void readFromStream(mrpt::serialization::CArchive &in)

Public Members

float minimum_points_clearance = 0.20f

Minimum distance between an inserted point and the existing ones in the map for it to be actually inserted.

float remove_submaps_farther_than = .0f

If !=0, remove the submap blocks farther (L1 distance) than this distance [meters]

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 &section) 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)

struct TRenderOptions : public mrpt::config::CLoadableOptions

Rendering options, used in getAs3DObject()

Public Functions

void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) 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_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