Class Filter

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class Filter : public pcl_ros::PCLNode<sensor_msgs::msg::PointCloud2>

Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.

Author

Radu Bogdan Rusu

Subclassed by pcl_ros::CropBox, pcl_ros::ExtractIndices, pcl_ros::PassThrough, pcl_ros::ProjectInliers, pcl_ros::RadiusOutlierRemoval, pcl_ros::StatisticalOutlierRemoval, pcl_ros::VoxelGrid

Public Types

typedef sensor_msgs::msg::PointCloud2 PointCloud2
typedef pcl::IndicesPtr IndicesPtr
typedef pcl::IndicesConstPtr IndicesConstPtr

Public Functions

Filter(std::string node_name, const rclcpp::NodeOptions &options)

Filter constructor.

Parameters:
  • node_name – node name

  • options – node options

Protected Functions

void use_frame_params()

declare and subscribe to param callback for input_frame and output_frame params

std::vector<std::string> add_common_params()

Add common parameters.

virtual void filter(const PointCloud2::ConstSharedPtr &input, const IndicesPtr &indices, PointCloud2 &output) = 0

Virtual abstract filter method. To be implemented by every child.

Parameters:
  • input – the input point cloud dataset.

  • indices – a pointer to the vector of point indices to use.

  • output – the resultant filtered PointCloud2

virtual void subscribe()

Lazy transport subscribe routine.

virtual void unsubscribe()

Lazy transport unsubscribe routine.

void computePublish(const PointCloud2::ConstSharedPtr &input, const IndicesPtr &indices)

Call the child filter () method, optionally transform the result, and publish it.

Parameters:
  • input – the input point cloud dataset.

  • indices – a pointer to the vector of point indices to use.

Protected Attributes

rclcpp::Subscription<PointCloud2>::SharedPtr sub_input_

The input PointCloud subscriber.

message_filters::Subscriber<PointCloud2> sub_input_filter_
std::string filter_field_name_

The desired user filter field name.

double filter_limit_min_

The minimum allowed filter value a point will be considered from.

double filter_limit_max_

The maximum allowed filter value a point will be considered from.

bool filter_limit_negative_

Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.

std::string tf_input_frame_

The input TF frame the data should be transformed into, if input.header.frame_id is different.

std::string tf_input_orig_frame_

The original data input TF frame.

std::string tf_output_frame_

The output TF frame the data should be transformed into, if input.header.frame_id is different.

std::mutex mutex_

Internal mutex.