extract_indices.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: extract_indices.h 35876 2011-02-09 01:04:36Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_FILTERS_EXTRACTINDICES_H_
39 #define PCL_ROS_FILTERS_EXTRACTINDICES_H_
40 
41 // PCL includes
42 #include <pcl/filters/extract_indices.h>
43 
44 #include "pcl_ros/filters/filter.h"
45 #include "pcl_ros/ExtractIndicesConfig.h"
46 
47 namespace pcl_ros
48 {
53  class ExtractIndices : public Filter
54  {
55  protected:
58 
64  inline void
65  filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
66  PointCloud2 &output)
67  {
68  boost::mutex::scoped_lock lock (mutex_);
69  pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
70  pcl_conversions::toPCL(*(input), *(pcl_input));
71  impl_.setInputCloud (pcl_input);
72  impl_.setIndices (indices);
73  pcl::PCLPointCloud2 pcl_output;
74  impl_.filter (pcl_output);
75  pcl_conversions::moveFromPCL(pcl_output, output);
76  }
77 
82  virtual bool
83  child_init (ros::NodeHandle &nh, bool &has_service);
84 
86  void
87  config_callback (pcl_ros::ExtractIndicesConfig &config, uint32_t level);
88 
89  private:
91  pcl::ExtractIndices<pcl::PCLPointCloud2> impl_;
92  public:
93  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94  };
95 }
96 
97 #endif //#ifndef PCL_ROS_FILTERS_EXTRACTINDICES_H_
98 
pcl_ros::ExtractIndices::impl_
pcl::ExtractIndices< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
Definition: extract_indices.h:91
pcl_ros::ExtractIndices
ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud.
Definition: extract_indices.h:53
filter.h
pcl_ros::Filter::mutex_
boost::mutex mutex_
Internal mutex.
Definition: filter.h:94
boost::shared_ptr
pcl_ros
Definition: boundary.h:46
pcl_ros::Filter::IndicesPtr
pcl::IndicesPtr IndicesPtr
Definition: filter.h:61
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
pcl_ros::ExtractIndices::filter
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
Definition: extract_indices.h:65
pcl_ros::ExtractIndices::srv_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::ExtractIndicesConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: extract_indices.h:57
pcl_ros::Filter
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
Definition: filter.h:56
pcl_ros::Filter::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:59
pcl_ros::ExtractIndices::config_callback
void config_callback(pcl_ros::ExtractIndicesConfig &config, uint32_t level)
Dynamic reconfigure service callback.
Definition: extract_indices.cpp:57
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
ros::NodeHandle
pcl_ros::ExtractIndices::child_init
virtual bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: extract_indices.cpp:43


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54