Class StatisticalOutlierRemoval
Defined in File statistical_outlier_removal.hpp
Inheritance Relationships
Base Type
public pcl_ros::Filter
(Class Filter)
Class Documentation
-
class StatisticalOutlierRemoval : public pcl_ros::Filter
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:
R. B. Rusu, Z. C. Marton, N. Blodow, M. Dolha, and M. Beetz. Towards 3D Point Cloud Based Object Maps for Household Environments Robotics and Autonomous Systems Journal (Special Issue on Semantic Knowledge), 2008.
- Author
Radu Bogdan Rusu
Note
setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
Public Functions
-
explicit EIGEN_MAKE_ALIGNED_OPERATOR_NEW StatisticalOutlierRemoval(const rclcpp::NodeOptions &options)
Protected Functions
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> ¶ms)
Parameter callback.
- Parameters:
params – parameter values to set
Protected Attributes
-
OnSetParametersCallbackHandle::SharedPtr callback_handle_