Contents
Users
Extract Indices
The ExtractIndices nodelet wraps the pcl::ExtractIndices filter (also see tutorial).
The following dynamic_reconfigure parameters are used:
Parameters
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.- Extract indices or the negative (all-indices)
PassThrough
The PassThrough nodelet wraps the pcl::PassThrough filter (also see PassThrough tutorial).
The following dynamic_reconfigure parameters are used:
Parameters
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.- The field name used for filtering
- The minimum allowed field value a point will be considered from Range: -1000.0 to 1000.0
- The maximum allowed field value a point will be considered from Range: -1000.0 to 1000.0
- Set to true if we want to return the data outside [filter_limit_min; filter_limit_max].
- The input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
- The output TF frame the data should be transformed into after processing, if input.header.frame_id is different.
ProjectInliers
The ProjectInliers nodelet wraps the pcl::ProjectInliers filter (also see Projection tutorial).
RadiusOutlierRemoval
The RadiusOutlierRemoval nodelet wraps the pcl::RadiusOutlierRemoval filter (also see Outlier removal tutorial).
StatisticalOutlierRemoval
The StatisticalOutlierRemoval nodelet wraps the pcl::StatisticalOutlierRemoval filter (also see Statistical outlier removal tutorial).
The following dynamic_reconfigure parameters are used:
Parameters
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.- The number of points (k) to use for mean distance estimation Range: 2 to 100
- The standard deviation multiplier threshold. All points outside the mean +- sigma * std_mul will be considered outliers. Range: 0.0 to 5.0
- Set whether the inliers should be returned (true) or the outliers (false)
VoxelGrid
The VoxelGrid nodelet wraps the pcl::VoxelGrid filter (also see Downsampling tutorial).
The following dynamic_reconfigure parameters are used:
Parameters
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.- The size of a leaf (on x,y,z) used for downsampling. Range: 0.0 to 1.0
- The field name used for filtering
- The minimum allowed field value a point will be considered from Range: -1000.0 to 1000.0
- The maximum allowed field value a point will be considered from Range: -1000.0 to 1000.0
- Set to true if we want to return the data outside [filter_limit_min; filter_limit_max].
- The input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
- The output TF frame the data should be transformed into after processing, if input.header.frame_id is different.
CropBox
The CropBox nodelet wraps the pcl::CropBox filter.
The following dynamic_reconfigure parameters are used:
Parameters
Dynamically Reconfigurable Parameters
- The minimum allowed x value a point will be considered from. Range: -1000.0 to 1000.0
- The maximum allowed x value a point will be considered from. Range: -1000.0 to 1000.0
- The minimum allowed y value a point will be considered from. Range: -1000.0 to 1000.0
- The maximum allowed y value a point will be considered from. Range: -1000.0 to 1000.0
- The minimum allowed z value a point will be considered from. Range: -1000.0 to 1000.0
- The maximum allowed z value a point will be considered from. Range: -1000.0 to 1000.0
- If true, the pointcloud shape (width, height) will be retained and filtered-out points will be set to nan. If false, pointcloud is reshaped to height 1 and filtered-out points are removed. Please not this is broken in Melodic and the pointcloud is always unorganized. In Noetic, it works correctly.
- Set to true if we want to return the data outside the limiting box. If false, data inside the box are returned.
- The input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
- The output TF frame the data should be transformed into after processing, if input.header.frame_id is different.
Developers
All pcl_ros nodelet filters inherit from pcl_ros::Filter, which requires that any class inheriting from it implement the following interface:
child_init(), filter(), onInit() and config_callback() are all virtual and can be overridden
filter (PointCloud2 &output) is pure abstract and must be implemented
if child_init (ros::NodeHandle &nh, bool &has_service) is implemented, and has_service is set to true, the Filter base class dynamic_reconfigure service will not be created
Common ROS parameters
The following ROS parameters are usually read on startup for any pcl_ros nodelet.
max_queue_size, int : defines the maximum queue size the ROS subscribers and publishers in the nodelet should use (see ros::NodeHandle::subscribe for more information).
use_indices, bool : usually indicates whether the nodelet should listen for incoming data on ~indices. This data represents a subset of point indices (pcl::PointIndices message) that should be used from the input dataset.
approximate_sync, bool : indicates whether the input topics that the nodelet listens to, should synchronize with an ApproximateTimeSynchronizer (their header.stamp can differ) or an ExactTimeSynchronizer (their header.stamp must be identical)
Input/Output topics
The following list of ROS topics are used by all pcl_ros filters:
input, in, sensor_msgs/PointCloud2 : input point cloud data to filter.
indices, in, pcl/PointIndices : input point cloud data indices to use from input.
output, out, sensor_msgs/PointCloud2 : the resultant filtered point cloud data.