38 #ifndef PCL_ROS_FILTERS_PASSTHROUGH_H_ 39 #define PCL_ROS_FILTERS_PASSTHROUGH_H_ 42 #include <pcl/filters/passthrough.h> 66 boost::mutex::scoped_lock lock (
mutex_);
67 pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
69 impl_.setInputCloud (pcl_input);
70 impl_.setIndices (indices);
71 pcl::PCLPointCloud2 pcl_output;
72 impl_.filter (pcl_output);
92 pcl::PassThrough<pcl::PCLPointCloud2>
impl_;
94 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
98 #endif //#ifndef PCL_ROS_FILTERS_PASSTHROUGH_H_
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
pcl::IndicesPtr IndicesPtr
sensor_msgs::PointCloud2 PointCloud2
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
pcl::PassThrough< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
boost::mutex mutex_
Internal mutex.
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given...
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.