filter.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: filter.h 35876 2011-02-09 01:04:36Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_FILTER_H_
39 #define PCL_ROS_FILTER_H_
40 
41 // PCL includes
42 #include <pcl/filters/filter.h>
43 #include "pcl_ros/pcl_nodelet.h"
44 
45 // Dynamic reconfigure
46 #include <dynamic_reconfigure/server.h>
47 #include "pcl_ros/FilterConfig.h"
48 
49 namespace pcl_ros
50 {
52 
57  class Filter : public PCLNodelet
58  {
59  public:
60  typedef sensor_msgs::PointCloud2 PointCloud2;
61 
64 
65  Filter () {}
66 
67  protected:
70 
72 
74  std::string filter_field_name_;
75 
78 
81 
84 
86  std::string tf_input_frame_;
87 
89  std::string tf_input_orig_frame_;
90 
92  std::string tf_output_frame_;
93 
95  boost::mutex mutex_;
96 
101  virtual bool
102  child_init (ros::NodeHandle &nh, bool &has_service)
103  {
104  has_service = false;
105  return (true);
106  }
107 
113  virtual void
114  filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
115  PointCloud2 &output) = 0;
116 
118  virtual void
119  subscribe();
120 
122  virtual void
123  unsubscribe();
124 
126  virtual void
127  onInit ();
128 
133  void
134  computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices);
135 
136  private:
139 
143 
145  virtual void
146  config_callback (pcl_ros::FilterConfig &config, uint32_t level);
147 
149  void
150  input_indices_callback (const PointCloud2::ConstPtr &cloud,
151  const PointIndicesConstPtr &indices);
152  public:
153  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
154  };
155 }
156 
157 #endif //#ifndef PCL_ROS_FILTER_H_
virtual void onInit()
Nodelet initialization routine.
Definition: filter.cpp:149
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: filter.h:138
virtual void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.
Definition: filter.cpp:177
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointIndices > > > sync_input_indices_a_
Definition: filter.h:142
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
Definition: filter.h:86
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
Definition: filter.h:92
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
Definition: filter.h:57
std::string tf_input_orig_frame_
The original data input TF frame.
Definition: filter.h:89
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: filter.h:80
virtual void unsubscribe()
Lazy transport unsubscribe routine.
Definition: filter.cpp:136
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:60
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)=0
Virtual abstract filter method. To be implemented by every child.
boost::mutex mutex_
Internal mutex.
Definition: filter.h:95
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:72
boost::shared_ptr< std::vector< int > > IndicesPtr
Definition: filter.h:62
virtual bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: filter.h:102
boost::shared_ptr< const std::vector< int > > IndicesConstPtr
Definition: filter.h:63
void input_indices_callback(const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
PointCloud2 + Indices data callback.
Definition: filter.cpp:194
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: filter.h:77
message_filters::Subscriber< PointCloud2 > sub_input_filter_
Definition: filter.h:71
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
Definition: filter.h:141
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
Definition: filter.h:83
void computePublish(const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
Call the child filter () method, optionally transform the result, and publish it. ...
Definition: filter.cpp:64
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83
std::string filter_field_name_
The desired user filter field name.
Definition: filter.h:74
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: filter.h:69
virtual void subscribe()
Lazy transport subscribe routine.
Definition: filter.cpp:107


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18