Template Class COctoMapBase

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public mrpt::maps::CMetricMap

Class Documentation

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

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 wurm2010octomap

See also

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

Public Types

using myself_t = COctoMapBase<octree_t, octree_node_t>

Public Functions

COctoMapBase(double resolution)

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

~COctoMapBase() override = default
template<class OCTOMAP_CLASS>
inline OCTOMAP_CLASS &getOctomap()

Get a reference to the internal octomap object. Example:

mrpt::maps::COctoMap  map;
octomap::OcTree &om = map.getOctomap<octomap::OcTree>();

inline std::string asString() const override

Returns a short description of the map.

void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
inline void getVisualizationInto(mrpt::viz::CSetOfObjects &o) const override

Returns a 3D object representing the map.

See also

renderingOptions

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

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

See also

renderingOptions

bool getPointOccupancy(const float x, const float y, const float 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.

void insertPointCloud(const CPointsMap &ptMap, const float sensor_x, const float sensor_y, const float sensor_z)

Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the sensor (the origin of the rays) in this map’s frame of reference. Insertion parameters can be found in insertionOptions.

See also

The generic observation insertion method CMetricMap::insertObservation()

bool castRay(const mrpt::math::TPoint3D &origin, const mrpt::math::TPoint3D &direction, mrpt::math::TPoint3D &end, bool ignoreUnknownCells = false, double maxRange = -1.0) const

Performs raycasting in 3d, similar to computeRay().

A ray is cast from origin with a given direction, the first occupied cell is returned (as center coordinate). If the starting coordinate is already occupied in the tree, this coordinate will be returned as a hit.

Parameters:
  • origin – starting coordinate of ray

  • direction – A vector pointing in the direction of the raycast. Does not need to be normalized.

  • end – returns the center of the cell that was hit by the ray, if successful

  • ignoreUnknownCells – whether unknown cells are ignored. If false (default), the raycast aborts when an unkown cell is hit.

  • maxRange – Maximum range after which the raycast is aborted (<= 0: no limit, default)

Returns:

whether or not an occupied cell was hit

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

Public Members

TInsertionOptions insertionOptions

The options used when inserting

TLikelihoodOptions likelihoodOptions
TRenderingOptions renderingOptions

Protected Functions

template<class octomap_point3d, class octomap_pointcloud>
bool internal_build_PointCloud_for_observation(const mrpt::obs::CObservation &obs, const std::optional<const mrpt::poses::CPose3D> &robotPose, octomap_point3d &sensorPt, octomap_pointcloud &scan) const

Builds the list of 3D points in global coordinates for a generic observation. Used for both, insertObservation() and computeLikelihood().

Parameters:
  • point3d_sensorPt[out] Is a pointer to a “point3D”.

  • ptr_scan[out] Is in fact a pointer to “octomap::Pointcloud”. Not declared as such to avoid headers dependencies in user code.

Returns:

false if the observation kind is not applicable.

Protected Attributes

mrpt::pimpl<Impl> m_impl
struct TInsertionOptions : public mrpt::config::CLoadableOptions

With this struct options are provided to the observation insertion process.

See also

CObservation::insertObservationInto()

Public Functions

TInsertionOptions(myself_t &parent)

Initialization of default parameters

TInsertionOptions()

Special constructor, not attached to a real COctoMap object: used only in limited situations, since get*() methods don’t work, etc.

inline TInsertionOptions(const TInsertionOptions &o)
inline TInsertionOptions &operator=(const TInsertionOptions &o)
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string &section) override
void dumpToTextStream(std::ostream &out) const override
inline void setOccupancyThres(double prob)

insertion (default: true)

(key name in .ini files: “occupancyThres”) sets the threshold for occupancy (sensor model) (Default=0.5)

inline void setProbHit(double prob)

(key name in .ini files: “probHit”)sets the probablility for a “hit” (will be converted to logodds) - sensor model (Default=0.7)

inline void setProbMiss(double prob)

(key name in .ini files: “probMiss”)sets the probablility for a “miss” (will be converted to logodds) - sensor model (Default=0.4)

inline void setClampingThresMin(double thresProb)

(key name in .ini files: “clampingThresMin”)sets the minimum threshold for occupancy clamping (sensor model) (Default=0.1192, -2 in log odds)

inline void setClampingThresMax(double thresProb)

(key name in .ini files: “clampingThresMax”)sets the maximum threshold for occupancy clamping (sensor model) (Default=0.971, 3.5 in log odds)

inline double getOccupancyThres() const
Returns:

threshold (probability) for occupancy - sensor model

inline float getOccupancyThresLog() const
Returns:

threshold (logodds) for occupancy - sensor model

inline double getProbHit() const
Returns:

probablility for a “hit” in the sensor model (probability)

inline float getProbHitLog() const
Returns:

probablility for a “hit” in the sensor model (logodds)

inline double getProbMiss() const
Returns:

probablility for a “miss” in the sensor model (probability)

inline float getProbMissLog() const
Returns:

probablility for a “miss” in the sensor model (logodds)

inline double getClampingThresMin() const
Returns:

minimum threshold for occupancy clamping in the sensor model (probability)

inline float getClampingThresMinLog() const
Returns:

minimum threshold for occupancy clamping in the sensor model (logodds)

inline double getClampingThresMax() const
Returns:

maximum threshold for occupancy clamping in the sensor model (probability)

inline float getClampingThresMaxLog() const
Returns:

maximum threshold for occupancy clamping in the sensor model (logodds)

Public Members

double maxrange = {-1.}

maximum range for how long individual beams are

bool pruning = {true}

inserted (default -1: complete beam)

whether the tree is (losslessly) pruned after

struct TLikelihoodOptions : public mrpt::config::CLoadableOptions

observations in the map

Options used when evaluating “computeObservationLikelihood”

See also

CObservation::computeObservationLikelihood

Public Functions

TLikelihoodOptions()

Initialization of default parameters

~TLikelihoodOptions() override = 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

Binary dump to stream

void readFromStream(mrpt::serialization::CArchive &in)

Binary dump to stream

Public Members

uint32_t decimation = {1}

Speed up the likelihood computation by considering only one out of N rays (default=1)

struct TRenderingOptions

Options for the conversion of a mrpt::maps::COctoMap into a mrpt::viz::COctoMapVoxels

Public Functions

TRenderingOptions() = default

generateFreeVoxels=true) (Default=true)

void writeToStream(mrpt::serialization::CArchive &out) const

Binary dump to stream

void readFromStream(mrpt::serialization::CArchive &in)

Binary dump to stream

Public Members

bool generateGridLines = {false}

Generate grid lines for all octree nodes,

bool generateOccupiedVoxels = {true}

useful to draw the “structure” of the octree, but computationally costly (Default: false) Generate voxels for the occupied

bool visibleOccupiedVoxels = {true}

volumes (Default=true)

Set occupied voxels visible (requires

bool generateFreeVoxels = {true}

generateOccupiedVoxels=true) (Default=true) Generate voxels for the freespace

bool visibleFreeVoxels = {true}

(Default=true)

Set free voxels visible (requires