Class ProbabilisticMap
Defined in File probabilistic_map.hpp
Nested Relationships
Nested Types
Class Documentation
-
class ProbabilisticMap
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
Public Types
-
using Vector3D = Eigen::Vector3d
Public Functions
-
ProbabilisticMap(double resolution)
-
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
-
float queryProbability(const Eigen::Vector3f &p_world) const
Public Static Functions
-
static inline 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)
Public Static Attributes
-
static const int32_t UnknownProbability
-
struct Options
These default values are the same as OctoMap.
-
using Vector3D = Eigen::Vector3d