class mrpt::maps::CVoxelMap

Overview

Log-odds sparse voxel map for cells containing only the occupancy of each voxel.

#include <mrpt/maps/CVoxelMap.h>

class CVoxelMap: public mrpt::maps::CVoxelMapOccupancyBase
{
public:
    // fields

    double resolution = 0.10;
    uint8_t inner_bits = 2;
    uint8_t leaf_bits = 3;
    mrpt::maps::TVoxelMap_InsertionOptions insertionOpts;
    mrpt::maps::TVoxelMap_LikelihoodOptions likelihoodOpts;
    TVoxelMap_InsertionOptions insertionOptions;

    // construction

    CVoxelMap(
        double resolution = 0.05,
        uint8_t inner_bits = 2,
        uint8_t leaf_bits = 3
        );

    // methods

    virtual void nn_prepare_for_2d_queries() const;
    virtual void nn_prepare_for_3d_queries() const;
    virtual bool nn_has_indices_or_ids() const;
    virtual size_t nn_index_count() const;

    virtual bool nn_single_search(
        const mrpt::math::TPoint3Df& query,
        mrpt::math::TPoint3Df& result,
        float& out_dist_sqr,
        uint64_t& resultIndexOrID
        ) const;

    virtual 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;

    virtual 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;

    virtual bool isEmpty() const;
    virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels& gl_obj) const;
    void updateVoxel(const double x, const double y, const double z, bool occupied);
    bool getPointOccupancy(const double x, const double y, const double z, double& prob_occupancy) const;
    mrpt::maps::CSimplePointsMap::Ptr getOccupiedVoxels() const;
    virtual mrpt::math::TBoundingBoxf boundingBox() const;
    void updateCell_fast_occupied(VoxelNodeOccupancy* theCell, const int8_t logodd_obs, const int8_t thres);
    void updateCell_fast_occupied(const Bonxai::CoordT& coord, const int8_t logodd_obs, const int8_t thres);
    void updateCell_fast_free(VoxelNodeOccupancy* theCell, const int8_t logodd_obs, const int8_t thres);
    void updateCell_fast_free(const Bonxai::CoordT& coord, const int8_t logodd_obs, const int8_t thres);
    virtual std::string asString() const;
    virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& o) const;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const;
    static CLogOddsGridMapLUT<occupancy_value_t>& get_logodd_lut();
    static float l2p(const occupancy_value_t l);
    static uint8_t l2p_255(const occupancy_value_t l);
    static occupancy_value_t p2l(const float p);
};

Inherited Members

public:
    // structs

    struct Impl;

    // fields

    static constexpr int8_t CELLTYPE_MIN = -127;
    static constexpr int8_t CELLTYPE_MAX = 127;
    static constexpr int8_t P2LTABLE_SIZE = CELLTYPE_MAX;
    static constexpr std::size_t LOGODDS_LUT_ENTRIES = 1<<8;

    // methods

    virtual bool isEmpty() const = 0;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0;
    virtual std::string asString() const = 0;
    virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& o) const = 0;
    CVoxelMapBase& operator = (const CVoxelMapBase& o);
    CVoxelMapBase& operator = (CVoxelMapBase&& o);
    virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels& gl_obj) const = 0;
    virtual bool nn_has_indices_or_ids() const = 0;
    virtual size_t nn_index_count() const = 0;

    virtual bool nn_single_search(
        const mrpt::math::TPoint3Df& query,
        mrpt::math::TPoint3Df& result,
        float& out_dist_sqr,
        uint64_t& resultIndexOrIDOrID
        ) const = 0;

    virtual bool nn_single_search(
        const mrpt::math::TPoint2Df& query,
        mrpt::math::TPoint2Df& result,
        float& out_dist_sqr,
        uint64_t& resultIndexOrIDOrID
        ) const = 0;

    virtual 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 = 0;

    virtual 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 = 0;

    virtual 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 = 0
        ) const = 0;

    virtual 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 = 0
        ) const = 0;

Fields

TVoxelMap_InsertionOptions insertionOptions

The options used when inserting observations in the map:

Methods

virtual void nn_prepare_for_2d_queries() const

Must be called before calls to nn_*_search() to ensure the required data structures are ready for queries (e.g.

KD-trees). Useful in multithreading applications.

virtual void nn_prepare_for_3d_queries() const

Must be called before calls to nn_*_search() to ensure the required data structures are ready for queries (e.g.

KD-trees). Useful in multithreading applications.

virtual bool nn_has_indices_or_ids() const

Returns true if the rest of nn_* methods will populate the output indices values with 0-based contiguous indices.

Returns false if indices are actually sparse ID numbers without any expectation of they be contiguous or start near zero.

virtual size_t nn_index_count() const

If nn_has_indices_or_ids() returns true, this must return the number of “points” (or whatever entity) the indices correspond to.

Otherwise, the return value should be ignored.

virtual bool nn_single_search(
    const mrpt::math::TPoint3Df& query,
    mrpt::math::TPoint3Df& result,
    float& out_dist_sqr,
    uint64_t& resultIndexOrID
    ) const

Search for the closest 3D point to a given one.

Parameters:

query

The query input point.

result

The found closest point.

out_dist_sqr

The square Euclidean distance between the query and the returned point.

resultIndexOrID

The index or ID of the result point in the map.

Returns:

True if successful, false if no point was found.

virtual 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

Search for the N closest 3D points to a given one.

Parameters:

query

The query input point.

results

The found closest points.

out_dists_sqr

The square Euclidean distances between the query and the returned point.

resultIndicesOrIDs

The indices or IDs of the result points.

virtual 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

Radius search for closest 3D points to a given one.

Parameters:

query

The query input point.

search_radius_sqr

The search radius, squared.

results

The found closest points.

out_dists_sqr

The square Euclidean distances between the query and the returned point.

resultIndicesOrIDs

The indices or IDs of the result points.

maxPoints

If !=0, the maximum number of neigbors to return.

virtual bool isEmpty() const

Returns true if the map is empty/no observation has been inserted.

virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels& gl_obj) const

Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.

Implementation defined for each children class.

See also:

renderingOptions

void updateVoxel(const double x, const double y, const double z, bool occupied)

Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false), using the log-odds parameters in insertionOptions.

bool getPointOccupancy(
    const double x,
    const double y,
    const double z,
    double& prob_occupancy
    ) const

Get the occupancy probability [0,1] of a point.

Returns:

false if the point is not mapped, in which case the returned “prob” is undefined.

mrpt::maps::CSimplePointsMap::Ptr getOccupiedVoxels() const

Returns all occupied voxels as a point cloud.

The shared_ptr is also hold and updated internally, so it is not safe to read it while also updating the voxel map in another thread.

The point cloud is cached, and invalidated upon map updates.

A voxel is considered occupied if its occupancy is larger than likelihoodOptions.occupiedThreshold (Range: [0,1], default: 0.6)

virtual mrpt::math::TBoundingBoxf boundingBox() const

This visits all cells to calculate a bounding box, caching the result so subsequent calls are cheap until the voxelmap is changed in some way.

void updateCell_fast_occupied(
    VoxelNodeOccupancy* theCell,
    const int8_t logodd_obs,
    const int8_t thres
    )

Performs Bayesian fusion of a new observation of a cell.

This method increases the “occupancy-ness” of a cell, managing possible saturation.

Parameters:

theCell

The cell to modify

logodd_obs

Observation of the cell, in log-odd form as transformed by p2l.

thres

This must be CELLTYPE_MIN+logodd_obs

See also:

updateCell, updateCell_fast_free

void updateCell_fast_occupied(
    const Bonxai::CoordT& coord,
    const int8_t logodd_obs,
    const int8_t thres
    )

Performs Bayesian fusion of a new observation of a cell.

This method increases the “occupancy-ness” of a cell, managing possible saturation.

Parameters:

coord

Cell indexes.

logodd_obs

Observation of the cell, in log-odd form as transformed by p2l.

thres

This must be CELLTYPE_MIN+logodd_obs

See also:

updateCell, updateCell_fast_free

void updateCell_fast_free(
    VoxelNodeOccupancy* theCell,
    const int8_t logodd_obs,
    const int8_t thres
    )

Performs Bayesian fusion of a new observation of a cell.

This method increases the “free-ness” of a cell, managing possible saturation.

Parameters:

logodd_obs

Observation of the cell, in log-odd form as transformed by p2l.

thres

This must be CELLTYPE_MAX-logodd_obs

See also:

updateCell_fast_occupied

void updateCell_fast_free(
    const Bonxai::CoordT& coord,
    const int8_t logodd_obs,
    const int8_t thres
    )

Performs the Bayesian fusion of a new observation of a cell.

This method increases the “free-ness” of a cell, managing possible saturation.

Parameters:

coord

Cell indexes.

logodd_obs

Observation of the cell, in log-odd form as transformed by p2l.

thres

This must be CELLTYPE_MAX-logodd_obs

See also:

updateCell_fast_occupied

virtual std::string asString() const

Returns a short description of the map.

virtual void getVisualizationInto(mrpt::opengl::CSetOfObjects& o) const

Returns a 3D object representing the map.

See also:

renderingOptions

virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const

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).

static CLogOddsGridMapLUT<occupancy_value_t>& get_logodd_lut()

Lookup tables for log-odds.

static float l2p(const occupancy_value_t l)

Scales an integer representation of the log-odd into a real valued probability in [0,1], using p=exp(l)/(1+exp(l))

static uint8_t l2p_255(const occupancy_value_t l)

Scales an integer representation of the log-odd into a linear scale [0,255], using p=exp(l)/(1+exp(l))

static occupancy_value_t p2l(const float p)

Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the valid range of voxel_node_t.