class mrpt::maps::COctoMap

A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the “octomap” C++ library.

This version only stores occupancy information at each octree node. See the base class mrpt::maps::COctoMapBase.

See also:

CMetricMap, the example in “MRPT/samples/octomap_simple”

#include <mrpt/maps/COctoMap.h>

class COctoMap: public mrpt::maps::COctoMapBase
{
public:
    //
fields

    double resolution {       0.10};
    mrpt::maps::COctoMap::TInsertionOptions insertionOpts;
    mrpt::maps::COctoMap::TLikelihoodOptions likelihoodOpts;

    // construction

    COctoMap(const double resolution = 0.10);

    //
methods

    void insertRay(
        const float end_x,
        const float end_y,
        const float end_z,
        const float sensor_x,
        const float sensor_y,
        const float sensor_z
        );

    void updateVoxel(const double x, const double y, const double z, bool occupied);
    bool isPointWithinOctoMap(const float x, const float y, const float z) const;
    double getResolution() const;
    unsigned int getTreeDepth() const;
    size_t size() const;
    size_t memoryUsage() const;
    size_t memoryUsageNode() const;
    size_t memoryFullGrid() const;
    double volume();
    void getMetricSize(double& x, double& y, double& z);
    void getMetricSize(double& x, double& y, double& z) const;
    void getMetricMin(double& x, double& y, double& z);
    void getMetricMin(double& x, double& y, double& z) const;
    void getMetricMax(double& x, double& y, double& z);
    void getMetricMax(double& x, double& y, double& z) const;
    size_t calcNumNodes() const;
    size_t getNumLeafNodes() const;
    virtual void setOccupancyThres(double prob);
    virtual void setProbHit(double prob);
    virtual void setProbMiss(double prob);
    virtual void setClampingThresMin(double thresProb);
    virtual void setClampingThresMax(double thresProb);
    virtual double getOccupancyThres() const;
    virtual float getOccupancyThresLog() const;
    virtual double getProbHit() const;
    virtual float getProbHitLog() const;
    virtual double getProbMiss() const;
    virtual float getProbMissLog() const;
    virtual double getClampingThresMin() const;
    virtual float getClampingThresMinLog() const;
    virtual double getClampingThresMax() const;
    virtual float getClampingThresMaxLog() const;
    virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels& gl_obj) const;
    virtual bool isEmpty() const;
};

Inherited Members

public:
    // typedefs

    typedef COctoMapBase<octree_t, octree_node_t> myself_t;

    // structs

    struct TInsertionOptions;
    struct TLikelihoodOptions;
    struct TRenderingOptions;

    //
fields

    TLikelihoodOptions likelihoodOptions;
    TRenderingOptions renderingOptions;

    //
methods

    virtual bool isEmpty() const = 0;
    virtual void saveMetricMapRepresentationToFile(const std::string& filNamePrefix) const = 0;
    virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr& outObj) const = 0;
    virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels& gl_obj) const = 0;
    virtual void setOccupancyThres(double prob) = 0;
    virtual void setProbHit(double prob) = 0;
    virtual void setProbMiss(double prob) = 0;
    virtual void setClampingThresMin(double thresProb) = 0;
    virtual void setClampingThresMax(double thresProb) = 0;
    virtual double getOccupancyThres() const = 0;
    virtual float getOccupancyThresLog() const = 0;
    virtual double getProbHit() const = 0;
    virtual float getProbHitLog() const = 0;
    virtual double getProbMiss() const = 0;
    virtual float getProbMissLog() const = 0;
    virtual double getClampingThresMin() const = 0;
    virtual float getClampingThresMinLog() const = 0;
    virtual double getClampingThresMax() const = 0;
    virtual float getClampingThresMaxLog() const = 0;

Fields

double resolution {         0.10}

The finest resolution of the octomap (default: 0.10.

mrpt::maps::COctoMap::TInsertionOptions insertionOpts

meters)

Observations insertion options

mrpt::maps::COctoMap::TLikelihoodOptions likelihoodOpts

Probabilistic observation likelihood options.

Construction

COctoMap(const double resolution = 0.10)

Default constructor.

Methods

void insertRay(
    const float end_x,
    const float end_y,
    const float end_z,
    const float sensor_x,
    const float sensor_y,
    const float sensor_z
    )

Just like insertPointCloud but with a single ray.

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 isPointWithinOctoMap(const float x, const float y, const float z) const

Check whether the given point lies within the volume covered by the octomap (that is, whether it is “mapped”)

size_t size() const

Returns:

The number of nodes in the tree

size_t memoryUsage() const

Returns:

Memory usage of the complete octree in bytes (may vary between architectures)

size_t memoryUsageNode() const

Returns:

Memory usage of the a single octree node

size_t memoryFullGrid() const

Returns:

Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)

void getMetricSize(double& x, double& y, double& z)

Size of OcTree (all known space) in meters for x, y and z dimension.

void getMetricSize(double& x, double& y, double& z) const

Size of OcTree (all known space) in meters for x, y and z dimension.

void getMetricMin(double& x, double& y, double& z)

minimum value of the bounding box of all known space in x, y, z

void getMetricMin(double& x, double& y, double& z) const

minimum value of the bounding box of all known space in x, y, z

void getMetricMax(double& x, double& y, double& z)

maximum value of the bounding box of all known space in x, y, z

void getMetricMax(double& x, double& y, double& z) const

maximum value of the bounding box of all known space in x, y, z

size_t calcNumNodes() const

Traverses the tree to calculate the total number of nodes.

size_t getNumLeafNodes() const

Traverses the tree to calculate the total number of leaf nodes.

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

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

virtual bool isEmpty() const

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