The ProbabilisticMap class is meant to behave as much as possible as octomap::Octree, given the same voxel size.
More...
#include <probabilistic_map.hpp>
|
| 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().
|
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
◆ Vector3D
◆ ProbabilisticMap()
| ProbabilisticMap |
( |
double | resolution | ) |
|
◆ addHitPoint()
| void addHitPoint |
( |
const Vector3D & | point | ) |
|
◆ addMissPoint()
| void addMissPoint |
( |
const Vector3D & | point | ) |
|
◆ getFreeVoxels()
◆ getOccupiedVoxels() [1/2]
◆ getOccupiedVoxels() [2/2]
template<typename PointT>
| void getOccupiedVoxels |
( |
std::vector< PointT > & | points | ) |
|
◆ grid() [1/2]
◆ grid() [2/2]
◆ 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
-
| points | a vector of points which represent detected obstacles |
| origin | origin of the point cloud |
| max_range | max range of the ray, if exceeded, we will use that to compute a free space |
◆ isFree()
◆ isOccupied()
◆ isUnknown()
◆ 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()
◆ prob()
| constexpr float prob |
( |
int32_t | logods_fixed | ) |
|
|
staticnodiscardconstexpr |
Expect the fixed comma value returned by logods().
◆ queryProbability() [1/2]
◆ queryProbability() [2/2]
| float queryProbability |
( |
const Eigen::Vector3f & | p_world | ) |
const |
|
nodiscard |
◆ setOptions()
| void setOptions |
( |
const Options & | options | ) |
|
◆ UnknownProbability
The documentation for this class was generated from the following files: