project_inliers.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, 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: project_inliers.h 35876 2011-02-09 01:04:36Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_FILTERS_PROJECT_INLIERS_H_
39 #define PCL_ROS_FILTERS_PROJECT_INLIERS_H_
40 
41 // PCL includes
42 #include <pcl/filters/project_inliers.h>
43 #include "pcl_ros/filters/filter.h"
44 
46 
47 namespace pcl_ros
48 {
50 
56  class ProjectInliers : public Filter
57  {
58  public:
60 
61  protected:
67  inline void
68  filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
69  PointCloud2 &output)
70  {
71  pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
72  pcl_conversions::toPCL (*(input), *(pcl_input));
73  impl_.setInputCloud (pcl_input);
74  impl_.setIndices (indices);
75  pcl::ModelCoefficients::Ptr pcl_model(new pcl::ModelCoefficients);
76  pcl_conversions::toPCL(*(model_), *(pcl_model));
77  impl_.setModelCoefficients (pcl_model);
78  pcl::PCLPointCloud2 pcl_output;
79  impl_.filter (pcl_output);
80  pcl_conversions::moveFromPCL(pcl_output, output);
81  }
82 
83  private:
86 
89 
94  pcl::ProjectInliers<pcl::PCLPointCloud2> impl_;
95 
97  virtual void
98  onInit ();
99 
101  void subscribe ();
102  void unsubscribe ();
103 
105  void
106  input_indices_model_callback (const PointCloud2::ConstPtr &cloud,
107  const PointIndicesConstPtr &indices,
108  const ModelCoefficientsConstPtr &model);
109  public:
110  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
111  };
112 }
113 
114 #endif //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_
filter.h
pcl_ros::ProjectInliers::filter
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
Definition: project_inliers.h:68
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::ProjectInliers::ProjectInliers
ProjectInliers()
Definition: project_inliers.h:59
pcl_ros::ProjectInliers::sync_input_indices_model_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointIndices, ModelCoefficients > > > sync_input_indices_model_e_
Synchronized input, indices, and model coefficients.
Definition: project_inliers.h:91
pcl_ros::ProjectInliers::unsubscribe
void unsubscribe()
Lazy transport unsubscribe routine.
Definition: project_inliers.cpp:114
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl_ros::ProjectInliers::sync_input_indices_model_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointIndices, ModelCoefficients > > > sync_input_indices_model_a_
Definition: project_inliers.h:92
message_filters::Subscriber< ModelCoefficients >
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::ProjectInliers::sub_model_
message_filters::Subscriber< ModelCoefficients > sub_model_
The message filter subscriber for model coefficients.
Definition: project_inliers.h:88
subscriber.h
pcl_ros::ProjectInliers::model_
ModelCoefficientsConstPtr model_
A pointer to the vector of model coefficients.
Definition: project_inliers.h:85
pcl_ros::PCLNodelet::ModelCoefficientsConstPtr
ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
Definition: pcl_nodelet.h:88
pcl_ros::ProjectInliers
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a sepa...
Definition: project_inliers.h:56
pcl_ros::ProjectInliers::impl_
pcl::ProjectInliers< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
Definition: project_inliers.h:94
message_filters::sync_policies
pcl_ros::ProjectInliers::subscribe
void subscribe()
NodeletLazy connection routine.
Definition: project_inliers.cpp:87
pcl_ros::Filter::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:59
pcl_ros::ProjectInliers::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: project_inliers.cpp:43
pcl_ros::ProjectInliers::input_indices_model_callback
void input_indices_model_callback(const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices, const ModelCoefficientsConstPtr &model)
PointCloud2 + Indices + Model data callback.
Definition: project_inliers.cpp:127
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)


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