Class ExtractIndices

Inheritance Relationships

Base Type

Class Documentation

class ExtractIndices : public pcl_ros::Filter

ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud.

Author

Radu Bogdan Rusu

Note

setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.

Public Functions

explicit EIGEN_MAKE_ALIGNED_OPERATOR_NEW ExtractIndices(const rclcpp::NodeOptions &options)

Protected Functions

inline virtual void filter(const PointCloud2::ConstSharedPtr &input, const IndicesPtr &indices, PointCloud2 &output) override

Call the actual filter.

Parameters:
  • input – the input point cloud dataset

  • indices – the input set of indices to use from input

  • output – the resultant filtered dataset

rcl_interfaces::msg::SetParametersResult config_callback(const std::vector<rclcpp::Parameter> &params)

Parameter callback.

Parameters:

params – parameter values to set

Protected Attributes

OnSetParametersCallbackHandle::SharedPtr callback_handle_