Easy Navigation
Loading...
Searching...
No Matches
PointPerceptionsOpsView Class Reference

Provides efficient, non-destructive, chainable operations over a set of point-based perceptions. More...

#include <PointPerception.hpp>

Classes

struct  VoxelKey
 Represents a discrete 3D voxel index for downsampling. More...
 
struct  VoxelKeyHash
 Hash function for VoxelKey. More...
 

Public Member Functions

pcl::PointCloud< pcl::PointXYZ > as_points () const
 Retrieves all selected points as a single cloud.
 
const pcl::PointCloud< pcl::PointXYZ > & as_points (int idx) const
 Retrieves the filtered point cloud for a specific perception.
 
std::shared_ptr< PointPerceptionsOpsViewcollapse (const std::vector< double > &collapse_dims) const
 Collapses dimensions to fixed values (e.g., project onto plane).
 
PointPerceptionsOpsViewdownsample (double resolution)
 Downsamples each perception using a voxel grid.
 
PointPerceptionsOpsViewfilter (const std::vector< double > &min_bounds, const std::vector< double > &max_bounds)
 Filters all point clouds by spatial bounds.
 
std::shared_ptr< PointPerceptionsOpsViewfuse (const std::string &target_frame) const
 Fuses all perceptions into one, transforming them to a common frame.
 
const PointPerceptionsget_perceptions () const
 Gets a reference to the underlying perceptions container.
 
 PointPerceptionsOpsView (const PointPerceptions &perceptions)
 Constructor using a constant reference to a container of perceptions.
 
 PointPerceptionsOpsView (PointPerceptions &&perceptions)
 Constructor that takes ownership of the container.
 

Detailed Description

Provides efficient, non-destructive, chainable operations over a set of point-based perceptions.

This class allows filtering, downsampling, fusion, and collapsing of multiple point clouds without duplicating memory, by using index-based views.

Constructor & Destructor Documentation

◆ PointPerceptionsOpsView() [1/2]

PointPerceptionsOpsView ( const PointPerceptions & perceptions)
explicit

Constructor using a constant reference to a container of perceptions.

Parameters
perceptionsContainer of perceptions to view.

◆ PointPerceptionsOpsView() [2/2]

PointPerceptionsOpsView ( PointPerceptions && perceptions)
explicit

Constructor that takes ownership of the container.

Parameters
perceptionsRvalue container of perceptions.

Member Function Documentation

◆ as_points() [1/2]

pcl::PointCloud< pcl::PointXYZ > as_points ( ) const

Retrieves all selected points as a single cloud.

Returns
Concatenated point cloud.

◆ as_points() [2/2]

const pcl::PointCloud< pcl::PointXYZ > & as_points ( int idx) const

Retrieves the filtered point cloud for a specific perception.

Parameters
idxIndex of the perception.
Returns
Const reference to the filtered point cloud.

◆ collapse()

std::shared_ptr< PointPerceptionsOpsView > collapse ( const std::vector< double > & collapse_dims) const

Collapses dimensions to fixed values (e.g., project onto plane).

Parameters
collapse_dimsFixed values for each axis (use NAN to preserve original values).
Returns
New view with collapsed points.

◆ downsample()

PointPerceptionsOpsView & downsample ( double resolution)

Downsamples each perception using a voxel grid.

Parameters
resolutionSize of the voxel in meters.
Returns
Reference to self for chaining.

◆ filter()

PointPerceptionsOpsView & filter ( const std::vector< double > & min_bounds,
const std::vector< double > & max_bounds )

Filters all point clouds by spatial bounds.

Parameters
min_boundsMinimum [x, y, z] values (use NAN to disable per axis).
max_boundsMaximum [x, y, z] values (use NAN to disable per axis).
Returns
Reference to self for chaining.

◆ fuse()

std::shared_ptr< PointPerceptionsOpsView > fuse ( const std::string & target_frame) const

Fuses all perceptions into one, transforming them to a common frame.

Parameters
target_frameFrame ID to transform all clouds into.
Returns
New fused PointPerceptionsOpsView.

◆ get_perceptions()

const PointPerceptions & get_perceptions ( ) const

Gets a reference to the underlying perceptions container.

Returns
Constant reference to PointPerceptions.

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