38 #ifndef PCL_ROS_FILTERS_EXTRACTINDICES_H_ 39 #define PCL_ROS_FILTERS_EXTRACTINDICES_H_ 42 #include <pcl/filters/extract_indices.h> 45 #include "pcl_ros/ExtractIndicesConfig.h" 68 boost::mutex::scoped_lock lock (
mutex_);
69 pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
71 impl_.setInputCloud (pcl_input);
72 impl_.setIndices (indices);
73 pcl::PCLPointCloud2 pcl_output;
74 impl_.filter (pcl_output);
87 config_callback (pcl_ros::ExtractIndicesConfig &config, uint32_t level);
91 pcl::ExtractIndices<pcl::PCLPointCloud2>
impl_;
93 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
97 #endif //#ifndef PCL_ROS_FILTERS_EXTRACTINDICES_H_
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
sensor_msgs::PointCloud2 PointCloud2
boost::mutex mutex_
Internal mutex.
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)