Fast occupancy grid with occupancy blocks and flat hashing for efficient point cloud overlap evaluation.
More...
#include <fast_occupancy_grid.hpp>
|
| | 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.
|
| |
Fast occupancy grid with occupancy blocks and flat hashing for efficient point cloud overlap evaluation.
◆ FastOccupancyGrid()
| gtsam_points::FastOccupancyGrid::FastOccupancyGrid |
( |
double |
resolution | ) |
|
Constructor.
- Parameters
-
| resolution | Voxel resolution. |
◆ calc_overlap()
| 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
-
| points | Point cloud. |
| pose | Pose of the points. |
- Returns
- Overlap ratio.
◆ calc_overlap_rate()
| 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
-
| points | Point cloud. |
| pose | Pose of the points. |
- Returns
- Overlap ratio.
◆ get_overlaps()
| 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
-
| points | Point cloud. |
| pose | Pose of the points. |
- Returns
- Overlap status of each point (0=free, 1=occupied).
◆ insert()
| void gtsam_points::FastOccupancyGrid::insert |
( |
const PointCloud & |
points, |
|
|
const Eigen::Isometry3d & |
pose = Eigen::Isometry3d::Identity() |
|
) |
| |
Insert points into the grid.
- Parameters
-
| points | Point cloud. |
| pose | Pose of the points. |
The documentation for this class was generated from the following files: