EasyNav Plugins
Loading...
Searching...
No Matches
ProbabilisticMap Class Reference

The ProbabilisticMap class is meant to behave as much as possible as octomap::Octree, given the same voxel size. More...

#include <probabilistic_map.hpp>

Collaboration diagram for ProbabilisticMap:

Classes

struct  CellT
struct  Options
 These default values are the same as OctoMap. More...

Public Types

using Vector3D = Eigen::Vector3d

Public Member Functions

void addHitPoint (const Vector3D &point)
void addMissPoint (const Vector3D &point)
void getFreeVoxels (std::vector< Bonxai::CoordT > &coords)
void getOccupiedVoxels (std::vector< Bonxai::CoordT > &coords)
template<typename PointT>
void getOccupiedVoxels (std::vector< PointT > &points)
VoxelGrid< CellT > & grid ()
const VoxelGrid< CellT > & grid () const
template<typename PointT, typename Alloc>
void insertPointCloud (const std::vector< PointT, Alloc > &points, const PointT &origin, double max_range)
template<typename PointT, typename Allocator>
void insertPointCloud (const std::vector< PointT, Allocator > &points, const PointT &origin, double max_range)
 insertPointCloud will update the probability map with a new set of detections.
bool isFree (const Bonxai::CoordT &coord) const
bool isOccupied (const Bonxai::CoordT &coord) const
bool isUnknown (const Bonxai::CoordT &coord) const
const Optionsoptions () const
 ProbabilisticMap (double resolution)
float queryProbability (const Bonxai::CoordT &coord) const
float queryProbability (const Eigen::Vector3f &p_world) const
void setOptions (const Options &options)

Static Public Member Functions

static constexpr int32_t logods (float prob)
 Compute the logds, but return the result as an integer, The real number is represented as a fixed precision integer (6 decimals after the comma).
static constexpr float prob (int32_t logods_fixed)
 Expect the fixed comma value returned by logods().

Static Public Attributes

static const int32_t UnknownProbability = ProbabilisticMap::logods(0.5f)

Detailed Description

The ProbabilisticMap class is meant to behave as much as possible as octomap::Octree, given the same voxel size.

Insert a point cloud to update the current probability

Member Typedef Documentation

◆ Vector3D

using Vector3D = Eigen::Vector3d

Constructor & Destructor Documentation

◆ ProbabilisticMap()

ProbabilisticMap ( double resolution)

Member Function Documentation

◆ addHitPoint()

void addHitPoint ( const Vector3D & point)

◆ addMissPoint()

void addMissPoint ( const Vector3D & point)

◆ getFreeVoxels()

void getFreeVoxels ( std::vector< Bonxai::CoordT > & coords)

◆ getOccupiedVoxels() [1/2]

void getOccupiedVoxels ( std::vector< Bonxai::CoordT > & coords)

◆ getOccupiedVoxels() [2/2]

template<typename PointT>
void getOccupiedVoxels ( std::vector< PointT > & points)

◆ grid() [1/2]

VoxelGrid< ProbabilisticMap::CellT > & grid ( )
nodiscard

◆ grid() [2/2]

const VoxelGrid< ProbabilisticMap::CellT > & grid ( ) const
nodiscard

◆ insertPointCloud() [1/2]

template<typename PointT, typename Alloc>
void insertPointCloud ( const std::vector< PointT, Alloc > & points,
const PointT & origin,
double max_range )

◆ insertPointCloud() [2/2]

template<typename PointT, typename Allocator>
void insertPointCloud ( const std::vector< PointT, Allocator > & points,
const PointT & origin,
double max_range )

insertPointCloud will update the probability map with a new set of detections.

The template function can accept points of different types, such as pcl:Point, Eigen::Vector or Bonxai::Point3d

Both origin and points must be in world coordinates

Parameters
pointsa vector of points which represent detected obstacles
originorigin of the point cloud
max_rangemax range of the ray, if exceeded, we will use that to compute a free space

◆ isFree()

bool isFree ( const Bonxai::CoordT & coord) const
nodiscard

◆ isOccupied()

bool isOccupied ( const Bonxai::CoordT & coord) const
nodiscard

◆ isUnknown()

bool isUnknown ( const Bonxai::CoordT & coord) const
nodiscard

◆ logods()

constexpr int32_t logods ( float prob)
staticnodiscardconstexpr

Compute the logds, but return the result as an integer, The real number is represented as a fixed precision integer (6 decimals after the comma).

◆ options()

const ProbabilisticMap::Options & options ( ) const
nodiscard

◆ prob()

constexpr float prob ( int32_t logods_fixed)
staticnodiscardconstexpr

Expect the fixed comma value returned by logods().

◆ queryProbability() [1/2]

float queryProbability ( const Bonxai::CoordT & coord) const
nodiscard

◆ queryProbability() [2/2]

float queryProbability ( const Eigen::Vector3f & p_world) const
nodiscard

◆ setOptions()

void setOptions ( const Options & options)

Member Data Documentation

◆ UnknownProbability

const int32_t UnknownProbability = ProbabilisticMap::logods(0.5f)
static

The documentation for this class was generated from the following files: