gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
gtsam_points::FastOccupancyGrid Class Reference

Fast occupancy grid with occupancy blocks and flat hashing for efficient point cloud overlap evaluation. More...

#include <fast_occupancy_grid.hpp>

Public Types

using Ptr = std::shared_ptr< FastOccupancyGrid >
 
using ConstPtr = std::shared_ptr< const FastOccupancyGrid >
 

Public Member Functions

 FastOccupancyGrid (double resolution)
 Constructor.
 
template<typename PointCloud >
void insert (const PointCloud &points, const Eigen::Isometry3d &pose=Eigen::Isometry3d::Identity())
 Insert points into the grid.
 
template<typename PointCloud >
int calc_overlap (const PointCloud &points, const Eigen::Isometry3d &pose=Eigen::Isometry3d::Identity()) const
 Calculate the number of points overlapping with the grid.
 
template<typename PointCloud >
double calc_overlap_rate (const PointCloud &points, const Eigen::Isometry3d &pose=Eigen::Isometry3d::Identity()) const
 Calculate the overlap ratio of the points with the grid.
 
template<typename PointCloud >
std::vector< unsigned char > get_overlaps (const PointCloud &points, const Eigen::Isometry3d &pose=Eigen::Isometry3d::Identity()) const
 Get the overlap status of each point in the point cloud.
 
int num_occupied_cells () const
 Get the number of occupied cells in the grid.
 

Detailed Description

Fast occupancy grid with occupancy blocks and flat hashing for efficient point cloud overlap evaluation.

Constructor & Destructor Documentation

◆ FastOccupancyGrid()

gtsam_points::FastOccupancyGrid::FastOccupancyGrid ( double  resolution)

Constructor.

Parameters
resolutionVoxel resolution.

Member Function Documentation

◆ calc_overlap()

template<typename PointCloud >
int gtsam_points::FastOccupancyGrid::calc_overlap ( const PointCloud points,
const Eigen::Isometry3d &  pose = Eigen::Isometry3d::Identity() 
) const

Calculate the number of points overlapping with the grid.

Parameters
pointsPoint cloud.
posePose of the points.
Returns
Overlap ratio.

◆ calc_overlap_rate()

template<typename PointCloud >
double gtsam_points::FastOccupancyGrid::calc_overlap_rate ( const PointCloud points,
const Eigen::Isometry3d &  pose = Eigen::Isometry3d::Identity() 
) const

Calculate the overlap ratio of the points with the grid.

Parameters
pointsPoint cloud.
posePose of the points.
Returns
Overlap ratio.

◆ get_overlaps()

template<typename PointCloud >
std::vector< unsigned char > gtsam_points::FastOccupancyGrid::get_overlaps ( const PointCloud points,
const Eigen::Isometry3d &  pose = Eigen::Isometry3d::Identity() 
) const

Get the overlap status of each point in the point cloud.

Parameters
pointsPoint cloud.
posePose of the points.
Returns
Overlap status of each point (0=free, 1=occupied).

◆ insert()

template<typename PointCloud >
void gtsam_points::FastOccupancyGrid::insert ( const PointCloud points,
const Eigen::Isometry3d &  pose = Eigen::Isometry3d::Identity() 
)

Insert points into the grid.

Parameters
pointsPoint cloud.
posePose of the points.

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