template class mrpt::maps::COctoMapBase

Overview

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

This base class represents a 3D map where each voxel may contain an “occupancy” property, RGBD data, etc. depending on the derived class.

As with any other mrpt::maps::CMetricMap, you can obtain a 3D representation of the map calling getAs3DObject() or getAsOctoMapVoxels()

To use octomap’s iterators to go through the voxels, use COctoMap::getOctomap()

The octomap library was presented in [8]

See also:

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

#include <mrpt/maps/COctoMapBase.h>

template <class octree_t, class octree_node_t>
class COctoMapBase: public mrpt::maps::CMetricMap
{
public:
    // typedefs

    typedef COctoMapBase<octree_t, octree_node_t> myself_t;

    // structs

    struct TInsertionOptions;
    struct TLikelihoodOptions;
    struct TRenderingOptions;

    // fields

    TLikelihoodOptions likelihoodOptions;
    TRenderingOptions renderingOptions;

    // construction

    COctoMapBase(double resolution);

    // methods

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

// direct descendants

class CColouredOctoMap;
class COctoMap;

Inherited Members

public:
    // 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;

Construction

COctoMapBase(double resolution)

Constructor, defines the resolution of the octomap (length of each voxel side)

Methods

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

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

See also:

renderingOptions