#include <segbot_velodyne_outlier_removal.h>

Protected Member Functions | |
| bool | child_init (ros::NodeHandle &nh, bool &has_service) |
| Child initialization routine. | |
| void | config_callback (segbot_sensors::SegbotVelodyneOutlierRemovalConfig &config, uint32_t level) |
| Dynamic reconfigure callback. | |
| void | filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) |
| Call the actual filter. | |
Protected Attributes | |
| boost::shared_ptr < dynamic_reconfigure::Server < SegbotVelodyneOutlierRemovalConfig > > | srv_ |
| Pointer to a dynamic reconfigure service. | |
Private Attributes | |
| std::vector< geometry_msgs::Point > | footprint_ |
| boost::shared_ptr< ros::Publisher > | footprint_publisher_ |
| std::string | frame_ |
Definition at line 163 of file segbot_velodyne_outlier_removal.h.
| bool segbot_sensors::SegbotVelodyneOutlierRemoval::child_init | ( | ros::NodeHandle & | nh, |
| bool & | has_service | ||
| ) | [protected, virtual] |
Child initialization routine.
| nh | ROS node handle |
| has_service | set to true if the child has a Dynamic Reconfigure service |
Reimplemented from pcl_ros::Filter.
Definition at line 244 of file segbot_velodyne_outlier_removal.cpp.
| void segbot_sensors::SegbotVelodyneOutlierRemoval::config_callback | ( | segbot_sensors::SegbotVelodyneOutlierRemovalConfig & | config, |
| uint32_t | level | ||
| ) | [protected] |
Dynamic reconfigure callback.
| config | the config object |
| level | the dynamic reconfigure level |
Definition at line 258 of file segbot_velodyne_outlier_removal.cpp.
| void segbot_sensors::SegbotVelodyneOutlierRemoval::filter | ( | const PointCloud2::ConstPtr & | input, |
| const IndicesPtr & | indices, | ||
| PointCloud2 & | output | ||
| ) | [inline, protected, virtual] |
Call the actual filter.
| input | the input point cloud dataset |
| indices | the input set of indices to use from input |
| output | the resultant filtered dataset |
Implements pcl_ros::Filter.
Definition at line 175 of file segbot_velodyne_outlier_removal.h.
std::vector<geometry_msgs::Point> segbot_sensors::SegbotVelodyneOutlierRemoval::footprint_ [private] |
Definition at line 223 of file segbot_velodyne_outlier_removal.h.
boost::shared_ptr<ros::Publisher> segbot_sensors::SegbotVelodyneOutlierRemoval::footprint_publisher_ [private] |
Definition at line 224 of file segbot_velodyne_outlier_removal.h.
Definition at line 225 of file segbot_velodyne_outlier_removal.h.
boost::shared_ptr<dynamic_reconfigure::Server<SegbotVelodyneOutlierRemovalConfig> > segbot_sensors::SegbotVelodyneOutlierRemoval::srv_ [protected] |
Pointer to a dynamic reconfigure service.
Reimplemented from pcl_ros::Filter.
Definition at line 167 of file segbot_velodyne_outlier_removal.h.