Provides efficient, non-destructive, chainable operations over a set of point-based perceptions.
More...
|
| PointPerceptionsOpsView & | add (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.
|
| |
| PointPerceptionsOpsView & | collapse (const std::vector< double > &collapse_dims, bool lazy=true) |
| | Collapses dimensions to fixed values (for example, projection onto a plane).
|
| |
| PointPerceptionsOpsView & | downsample (double resolution) |
| | Downsamples each perception using a voxel grid.
|
| |
| 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.
|
| |
| PointPerceptionsOpsView & | fuse (const std::string &target_frame, bool exact_time=true) |
| | Configures fusion of all perceptions into a common frame.
|
| |
| 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.
|
| |
| rclcpp::Time | get_latest_stamp () const |
| | Retrieves the latest timestamp across all perceptions.
|
| |
| const PointPerceptions & | get_perceptions () const |
| | Provides a constant reference to the underlying perceptions container.
|
| |
| PointPerceptionsOpsView & | operator= (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 |
| |
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()).
| 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
-
| points | Point cloud to include. |
| frame | Frame ID associated with points. |
| stamp | Timestamp associated with points. |
- Returns
- Reference to
*this to allow chaining.
| 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_bounds | Minimum [x,y,z] values (use NaN to disable per axis). |
| max_bounds | Maximum [x,y,z] values (use NaN to disable per axis). |
| lazy_post_fuse | If 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.
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_frame | Frame ID to which all clouds are conceptually transformed. |
| stamp | Reference to a rclcpp::Time variable where the effective timestamp will be stored. |
| exact_time | If 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.