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_ros/pcl_nodelet.h"
43 
44 // Dynamic reconfigure
45 #include <dynamic_reconfigure/server.h>
46 #include "pcl_ros/FilterConfig.h"
47 
48 namespace pcl_ros
49 {
51 
56  class Filter : public PCLNodelet
57  {
58  public:
59  typedef sensor_msgs::PointCloud2 PointCloud2;
60 
61  typedef pcl::IndicesPtr IndicesPtr;
62  typedef pcl::IndicesConstPtr IndicesConstPtr;
63 
64  Filter () {}
65 
66  protected:
69 
71 
73  std::string filter_field_name_;
74 
77 
80 
83 
85  std::string tf_input_frame_;
86 
88  std::string tf_input_orig_frame_;
89 
91  std::string tf_output_frame_;
92 
94  boost::mutex mutex_;
95 
100  virtual bool
101  child_init (ros::NodeHandle &/*nh*/, bool &has_service)
102  {
103  has_service = false;
104  return (true);
105  }
106 
112  virtual void
113  filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
114  PointCloud2 &output) = 0;
115 
117  virtual void
118  subscribe();
119 
121  virtual void
122  unsubscribe();
123 
125  virtual void
126  onInit ();
127 
132  void
133  computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices);
134 
135  private:
138 
142 
144  virtual void
145  config_callback (pcl_ros::FilterConfig &config, uint32_t level);
146 
148  void
149  input_indices_callback (const PointCloud2::ConstPtr &cloud,
150  const PointIndicesConstPtr &indices);
151  public:
152  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
153  };
154 }
155 
156 #endif //#ifndef PCL_ROS_FILTER_H_
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition: pcl_nodelet.h:73
pcl_ros::Filter::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: filter.cpp:148
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::config_callback
virtual void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.
Definition: filter.cpp:176
pcl_ros::Filter::IndicesPtr
pcl::IndicesPtr IndicesPtr
Definition: filter.h:61
pcl_ros::Filter::filter_limit_min_
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: filter.h:76
pcl_ros::Filter::tf_input_frame_
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:85
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl_nodelet.h
pcl_ros::Filter::input_indices_callback
void input_indices_callback(const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
PointCloud2 + Indices data callback.
Definition: filter.cpp:193
pcl_ros::Filter::filter_limit_negative_
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_)....
Definition: filter.h:82
message_filters::Subscriber< PointCloud2 >
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::subscribe
virtual void subscribe()
Lazy transport subscribe routine.
Definition: filter.cpp:106
pcl_ros::Filter::computePublish
void computePublish(const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
Call the child filter () method, optionally transform the result, and publish it.
Definition: filter.cpp:63
pcl_ros::Filter::filter_field_name_
std::string filter_field_name_
The desired user filter field name.
Definition: filter.h:73
pcl_ros::Filter::sync_input_indices_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointIndices > > > sync_input_indices_a_
Definition: filter.h:141
pcl_ros::Filter::sub_input_filter_
message_filters::Subscriber< PointCloud2 > sub_input_filter_
Definition: filter.h:70
pcl_ros::Filter::Filter
Filter()
Definition: filter.h:64
pcl_ros::Filter::srv_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: filter.h:137
pcl_ros::Filter::tf_output_frame_
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:91
message_filters::sync_policies
pcl_ros::Filter::tf_input_orig_frame_
std::string tf_input_orig_frame_
The original data input TF frame.
Definition: filter.h:88
pcl_ros::Filter::child_init
virtual bool child_init(ros::NodeHandle &, bool &has_service)
Child initialization routine.
Definition: filter.h:101
pcl_ros::Filter::sync_input_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
Definition: filter.h:140
pcl_ros::Filter::filter_limit_max_
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: filter.h:79
pcl_ros::Filter::unsubscribe
virtual void unsubscribe()
Lazy transport unsubscribe routine.
Definition: filter.cpp:135
pcl_ros::Filter::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:59
pcl_ros::Filter::IndicesConstPtr
pcl::IndicesConstPtr IndicesConstPtr
Definition: filter.h:62
pcl_ros::Filter::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: filter.h:68
pcl_ros::Filter::filter
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)=0
Virtual abstract filter method. To be implemented by every child.
ros::NodeHandle
ros::Subscriber


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40