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
 Discrete 3D voxel index used for downsampling. More...
 
struct  VoxelKeyHash
 Hash functor for VoxelKey. More...
 

Public Member Functions

PointPerceptionsOpsViewadd (const pcl::PointCloud< pcl::PointXYZ > points, const std::string &frame, rclcpp::Time stamp)
 Adds a new perception to the current view.
 
pcl::PointCloud< pcl::PointXYZ > as_points () const
 Retrieves all selected points across perceptions as a single concatenated cloud.
 
const pcl::PointCloud< pcl::PointXYZ > & as_points (int idx) const
 Retrieves the filtered point cloud for a specific perception.
 
PointPerceptionsOpsViewcollapse (const std::vector< double > &collapse_dims, bool lazy=true)
 Collapses dimensions to fixed values (for example, projection onto a plane).
 
PointPerceptionsOpsViewdownsample (double resolution)
 Downsamples each perception using a voxel grid.
 
PointPerceptionsOpsViewfilter (const std::vector< double > &min_bounds, const std::vector< double > &max_bounds, bool lazy_post_fuse=true)
 Filters all point clouds by axis-aligned bounds.
 
PointPerceptionsOpsViewfuse (const std::string &target_frame, bool exact_time=true)
 Configures fusion of all perceptions into a common frame.
 
PointPerceptionsOpsViewfuse (const std::string &target_frame, rclcpp::Time &stamp, bool exact_time=true)
 Configures fusion of all perceptions into a common frame, returning the effective stamp.
 
rclcpp::Time get_latest_stamp () const
 Retrieves the latest timestamp across all perceptions.
 
const PointPerceptionsget_perceptions () const
 Provides a constant reference to the underlying perceptions container.
 
PointPerceptionsOpsViewoperator= (const PointPerceptionsOpsView &)=delete
 
 PointPerceptionsOpsView (const PointPerception &perception)
 Constructs a view from a single PointPerception instance.
 
 PointPerceptionsOpsView (const PointPerceptions &perceptions)
 Constructs a view over an external container of perceptions.
 
 PointPerceptionsOpsView (const PointPerceptionsOpsView &)=delete
 
 PointPerceptionsOpsView (PointPerceptions &&perceptions)
 Constructs a view taking ownership of the container.
 
 PointPerceptionsOpsView (PointPerceptionsOpsView &&)=default
 

Detailed Description

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

This view enables filtering, downsampling, fusion, and dimensional collapsing across multiple point clouds without duplicating the underlying perceptions. Most operations work lazily by keeping index-based selections and transformation options, and only materialize a new point cloud when required (for example in as_points()).

Constructor & Destructor Documentation

◆ PointPerceptionsOpsView() [1/5]

PointPerceptionsOpsView ( const PointPerceptions & perceptions)
explicit

Constructs a view over an external container of perceptions.

Parameters
perceptionsConstant reference to the source container.

◆ PointPerceptionsOpsView() [2/5]

PointPerceptionsOpsView ( const PointPerception & perception)
explicit

Constructs a view from a single PointPerception instance.

Creates an internal container owning the given perception and initializes the index set for all its points.

Parameters
perceptionThe PointPerception to wrap in the view.

◆ PointPerceptionsOpsView() [3/5]

PointPerceptionsOpsView ( PointPerceptions && perceptions)
explicit

Constructs a view taking ownership of the container.

Parameters
perceptionsRvalue container of perceptions to be owned by the view.

◆ PointPerceptionsOpsView() [4/5]

◆ PointPerceptionsOpsView() [5/5]

Member Function Documentation

◆ add()

PointPerceptionsOpsView & add ( const pcl::PointCloud< pcl::PointXYZ > points,
const std::string & frame,
rclcpp::Time stamp )

Adds a new perception to the current view.

This method extends the underlying set of perceptions managed by the view. It does not create a new PointPerceptionsOpsView instance; instead, it updates the current view in place and returns a reference to *this to allow method chaining.

The newly added perception becomes part of subsequent operations such as filtering, fusion, collapsing, and final materialization (as_points()).

Parameters
pointsPoint cloud to include.
frameFrame ID associated with points.
stampTimestamp associated with points.
Returns
Reference to *this to allow chaining.

◆ as_points() [1/2]

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

Retrieves all selected points across perceptions as a single concatenated 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 target perception in the underlying container.
Returns
Const reference to the filtered point cloud.

◆ collapse()

PointPerceptionsOpsView & collapse ( const std::vector< double > & collapse_dims,
bool lazy = true )

Collapses dimensions to fixed values (for example, projection onto a plane).

Components set to NaN in collapse_dims keep the original values.

The behaviour depends on lazy:

  • If lazy is true (default), the collapse configuration is stored in the view and applied lazily when materializing point clouds (for example, in as_points()), without modifying the underlying perception data.
  • If lazy is false and the view owns its internal container, the collapse is applied eagerly by updating the coordinates of all stored points, so subsequent operations (filters, fusion, etc.) observe the collapsed geometry. On non-owning views, the eager mode is ignored to avoid modifying external data.
Parameters
collapse_dimsFixed values for each axis (use NaN to preserve original values).
lazyIf true, configure collapse lazily for output only; if false and the view is owning, apply the collapse immediately to the internal point data.
Returns
Reference to *this to allow chaining.

◆ downsample()

PointPerceptionsOpsView & downsample ( double resolution)

Downsamples each perception using a voxel grid.

Parameters
resolutionVoxel size in meters.
Returns
Reference to *this to allow chaining.

◆ filter()

PointPerceptionsOpsView & filter ( const std::vector< double > & min_bounds,
const std::vector< double > & max_bounds,
bool lazy_post_fuse = true )

Filters all point clouds by axis-aligned bounds.

When the view has no target frame configured (that is, fuse() has not been called), this method always performs an eager filtering step in the original frame of each sensor, updating the internal index sets in-place.

When a target frame has been configured via fuse(), the behaviour depends on lazy_post_fuse:

  • If lazy_post_fuse is true (default), the bounds are stored as a post-fuse filter in the target frame and are applied lazily during materialization (for example, in as_points()), without modifying the internal indices.
  • If lazy_post_fuse is false, the method applies the transform to the target frame immediately and performs an eager filtering step in that frame, updating the internal indices accordingly.

Components set to NaN in min_bounds or max_bounds leave the corresponding axis unbounded.

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).
lazy_post_fuseIf true and a target frame is set, configure a lazy post-fuse filter in the target frame; if false, always filter eagerly (updating indices) in the current frame (sensor or target).
Returns
Reference to *this to allow chaining.

◆ fuse() [1/2]

PointPerceptionsOpsView & fuse ( const std::string & target_frame,
bool exact_time = true )

Configures fusion of all perceptions into a common frame.

This method does not immediately build a fused point cloud. Instead, it stores the target frame and the required transforms so that subsequent operations (for example filter) and final materialization (as_points()) work in target_frame without duplicating the underlying data.

Parameters
target_frameFrame ID to which all clouds are conceptually transformed.
stampEffective timestamp for the TF lookup.
exact_timeIf true, TF lookups use the exact timestamp of each perception; if false (default), the most recent available transform is used.
Returns
Reference to *this to allow chaining.

◆ fuse() [2/2]

PointPerceptionsOpsView & fuse ( const std::string & target_frame,
rclcpp::Time & stamp,
bool exact_time = true )

Configures fusion of all perceptions into a common frame, returning the effective stamp.

This method does not immediately build a fused point cloud. Instead, it stores the target frame and the required transforms so that subsequent operations (for example filter) and final materialization (as_points()) work in target_frame without duplicating the underlying data.

The effective timestamp used for TF lookups is returned via the stamp parameter.

If exact_time is true, stamp is set to the timestamp of the most recent perception among those being fused; otherwise, it is set to the time at which the TF lookup is performed.

Parameters
target_frameFrame ID to which all clouds are conceptually transformed.
stampReference to a rclcpp::Time variable where the effective timestamp will be stored.
exact_timeIf true, TF lookups use the exact timestamp of each perception; if false (default), the most recent available transform is used.
Returns
Reference to *this to allow chaining.

◆ get_latest_stamp()

rclcpp::Time get_latest_stamp ( ) const

Retrieves the latest timestamp across all perceptions.

Returns
The most recent timestamp.

◆ get_perceptions()

const PointPerceptions & get_perceptions ( ) const

Provides a constant reference to the underlying perceptions container.

Returns
Constant reference to the container.

◆ operator=()

PointPerceptionsOpsView & operator= ( const PointPerceptionsOpsView & )
delete

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