Wrappers for some of the pcl filters for sensor_msgs/PointCloud2 ROS messages. The implementation and usage is based on the filter and sensor_filter packages, so it is different from the wrappers of the PCL filters provided by the package pcl_ros.
All the parameters are settable from the config file, but also online through the dynamic_reconfigure server.
Note that changing params with the dynamic_reconfigure server may take some seconds to have effect.
No ROS2 version (yet).
See launch and config folders
Wrapper for the pcl::PassThrough filter
active(bool, default: true) Activate the filter or not.input_frame(str, default: "") The input TF frame the data should be transformed into before processingoutput_frame(str, default: "") The output TF frame the data should be transformed into after processingpub_cloud(bool, default: false) Publish the cloud immediately after this filter. Note that this is a duplicate if the filter is the last in the chain. Useful for debug purposes and it will publish even ifactiveis false.keep_organized(bool, default: true) Keep the point cloud organized (pcl::FilterIndices<PointT>::setKeepOrganized (bool keep_organized)negative(bool, default: false) Set to true to return the data outside the min max limitsfilter_field_name(str, default: z) The field to be used for filtering datafilter_limit_min(double, default: 0) The minimum allowed field value a point will be consideredfilter_limit_max(double, default: 1) The maximum allowed field value a point will be considered
Wrapper for the pcl::CropBox filter.
Warning pcl::CrobBox parameter keep_organized is broken on ROS melodic (on noetic it is ok).
active(bool, default: true) Activate the filter or not.input_frame(str, default: "") The input TF frame the data should be transformed into before processingoutput_frame(str, default: "") The output TF frame the data should be transformed into after processingpub_cloud(bool, default: false) Publish the cloud immediately after this filter. Note that this is a duplicate if the filter is the last in the chain. Useful for debug purposes and it will publish even ifactiveis false.keep_organized(bool, default: true) Keep the point cloud organized (pcl::FilterIndices<PointT>::setKeepOrganized (bool keep_organized)negative(bool, default: false) Set to true to return the data outside the min max limitsmin_x(double, default: -1.0) The minimum allowed x value a point will be considered from. Range: -1000.0 to 1000.0max_x(double, default: -1.0) The maximum allowed x value a point will be considered from. Range: -1000.0 to 1000.0min_y(double, default: -1.0) The minimum allowed y value a point will be considered from. Range: -1000.0 to 1000.0max_y(double, default: -1.0) The maximum allowed y value a point will be considered from. Range: -1000.0 to 1000.0min_z(double, default: -1.0) The minimum allowed z value a point will be considered from. Range: -1000.0 to 1000.0max_z(double, default: -1.0) The maximum allowed z value a point will be considered from. Range: -1000.0 to 1000.0
Wrapper for the pcl::VoxelGrid filter.
active(bool, default: true) Activate the filter or not.input_frame(str, default: "") The input TF frame the data should be transformed into before processingoutput_frame(str, default: "") The output TF frame the data should be transformed into after processingpub_cloud(bool, default: false) Publish the cloud immediately after this filter. Note that this is a duplicate if the filter is the last in the chain. Useful for debug purposes and it will publish even ifactiveis false.negative(bool, default: false) Set to true to return the data outside the min max limitsleaf_size_x(double, default: 0.01) The size of a leaf (on x) used for downsampling. Range: 0.0 to 1.0leaf_size_y(double, default: 0.01) The size of a leaf (on y) used for downsampling. Range: 0.0 to 1.0leaf_size_z(double, default: 0.01) The size of a leaf (on z) used for downsampling. Range: 0.0 to 1.0min_points_per_voxel(int, default:0) Set the minimum number of points required for a voxel to be useddownsample_all_data(int, default:0) Set to true if all fields need to be downsampled, or false if just XYZfilter_field_name(str, default: "") The field to be used for filtering data, acting like a passthrough. Empty for not usingfilter_limit_min(double, default: -FLT_MAX) The minimum allowed field value a point will be consideredfilter_limit_max(double, default: FLT_MAX) The maximum allowed field value a point will be considered
Wrapper to extract a geometric model with pcl::SACSegmentation and pcl::ExtractIndices.
active(bool, default: true) Activate the filter or not.input_frame(str, default: "") The input TF frame the data should be transformed into before processingoutput_frame(str, default: "") The output TF frame the data should be transformed into after processingpub_cloud(bool, default: false) Publish the cloud immediately after this filter. Note that this is a duplicate if the filter is the last in the chain. Useful for debug purposes and it will publish even ifactiveis false.negative(bool, default: false) Set whether to filter out (remove) the model (true) or all the rest (false).model_type(int, default: 16) Geometric model to look for. Default toSACMODEL_PARALLEL_PLANE(15). Please use integers according to the linked enum. Some types require a SacSegmentationFromNormals which is currently not implemented. CheckSacSegmentationExtractPointCloud2.cfgfor the ones available. See also pcl official doc for params info.method_type(int, default: 0) Segmentation model to use for. Default toSAC_RANSAC(0) . Check pcl official doc. Please use integers according to the linked enum.axis_x(double, default: 0.0) The x component of the normal to the model to be removed. Range: 0.0 to 1.0axis_y(double, default: 0.0) The y component of the normal to the model to be removed. Range: 0.0 to 1.0axis_z(double, default: 1.0) The z component of the normal to the model to be removed. Range: 0.0 to 1.0eps_angle(double, default: 0.15) Tolerance angle (rad) to the model to be considered normal to the axis. Range: -3.15 to 3.15distance_threshold(double, default: 0.01) Range: 0 to 10optimize_coefficents(bool, default: 0.01) Optimize the coefficents or not.max_iterations(bool, default: 50)probability(bool, default: 0.99)min_radius(bool, default: -1)max_radius(bool, default: 1000)