sac_segmentation.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: sac_segmentation.h 35564 2011-01-27 07:32:12Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_SAC_SEGMENTATION_H_
39 #define PCL_ROS_SAC_SEGMENTATION_H_
40 
41 #include "pcl_ros/pcl_nodelet.h"
43 
44 // PCL includes
45 #include <pcl/segmentation/sac_segmentation.h>
46 
47 // Dynamic reconfigure
48 #include <dynamic_reconfigure/server.h>
49 #include "pcl_ros/SACSegmentationConfig.h"
50 #include "pcl_ros/SACSegmentationFromNormalsConfig.h"
51 
52 namespace pcl_ros
53 {
55 
57 
61  class SACSegmentation : public PCLNodelet
62  {
63  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
64  typedef PointCloud::Ptr PointCloudPtr;
65  typedef PointCloud::ConstPtr PointCloudConstPtr;
66 
67  public:
70 
74  inline void setInputTFframe (std::string tf_frame) { tf_input_frame_ = tf_frame; }
75 
77  inline std::string getInputTFframe () { return (tf_input_frame_); }
78 
82  inline void setOutputTFframe (std::string tf_frame) { tf_output_frame_ = tf_frame; }
83 
85  inline std::string getOutputTFframe () { return (tf_output_frame_); }
86 
87  protected:
88  // The minimum number of inliers a model must have in order to be considered valid.
90 
91  // ROS nodelet attributes
94 
97 
100 
103 
105  std::string tf_input_frame_;
106 
108  std::string tf_input_orig_frame_;
109 
111  std::string tf_output_frame_;
112 
116 
118  virtual void onInit ();
119 
121  virtual void subscribe ();
122  virtual void unsubscribe ();
123 
128  void config_callback (SACSegmentationConfig &config, uint32_t level);
129 
134  void input_indices_callback (const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices);
135 
140 
144  inline void
146  {
147  indices_ = *indices;
148  }
149 
153  inline void
154  input_callback (const PointCloudConstPtr &input)
155  {
156  indices_.header = fromPCL(input->header);
157  PointIndicesConstPtr indices;
158  indices.reset (new PointIndices (indices_));
159  nf_pi_.add (indices);
160  }
161 
162  private:
164  boost::mutex mutex_;
165 
167  pcl::SACSegmentation<pcl::PointXYZ> impl_;
168 
172 
173  public:
174  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
175  };
176 
178 
182  {
183  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
184  typedef PointCloud::Ptr PointCloudPtr;
185  typedef PointCloud::ConstPtr PointCloudConstPtr;
186 
187  typedef pcl::PointCloud<pcl::Normal> PointCloudN;
188  typedef PointCloudN::Ptr PointCloudNPtr;
189  typedef PointCloudN::ConstPtr PointCloudNConstPtr;
190 
191  public:
195  inline void setInputTFframe (std::string tf_frame) { tf_input_frame_ = tf_frame; }
196 
198  inline std::string getInputTFframe () { return (tf_input_frame_); }
199 
203  inline void setOutputTFframe (std::string tf_frame) { tf_output_frame_ = tf_frame; }
204 
206  inline std::string getOutputTFframe () { return (tf_output_frame_); }
207 
208  protected:
209  // ROS nodelet attributes
212 
215 
218 
223  inline void
224  input_callback (const PointCloudConstPtr &cloud)
225  {
226  PointIndices indices;
227  indices.header.stamp = fromPCL(cloud->header).stamp;
228  nf_.add (boost::make_shared<PointIndices> (indices));
229  }
230 
234 
236  std::string tf_input_frame_;
238  std::string tf_input_orig_frame_;
240  std::string tf_output_frame_;
241 
243  virtual void onInit ();
244 
246  virtual void subscribe ();
247  virtual void unsubscribe ();
248 
252  void axis_callback (const pcl_msgs::ModelCoefficientsConstPtr &model);
253 
258  void config_callback (SACSegmentationFromNormalsConfig &config, uint32_t level);
259 
265  void input_normals_indices_callback (const PointCloudConstPtr &cloud,
266  const PointCloudNConstPtr &cloud_normals,
267  const PointIndicesConstPtr &indices);
268 
269  private:
271  boost::mutex mutex_;
272 
274  pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal> impl_;
275 
279 
280  public:
281  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
282  };
283 }
284 
285 #endif //#ifndef PCL_ROS_SAC_SEGMENTATION_H_
ros::Publisher pub_model_
The output ModelCoefficients publisher.
pcl::PointCloud< pcl::PointXYZ > PointCloud
boost::mutex mutex_
Internal mutex.
virtual void subscribe()
LazyNodelet connection routine.
void input_callback(const PointCloudConstPtr &input)
Input callback. Used when latched_indices_ is set.
void config_callback(SACSegmentationConfig &config, uint32_t level)
Dynamic reconfigure callback.
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointIndices > > > sync_input_indices_a_
std::string tf_input_orig_frame_
The original data input TF frame.
PointCloud::Ptr PointCloudPtr
void input_callback(const PointCloudConstPtr &cloud)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
boost::mutex mutex_
Internal mutex.
void setOutputTFframe(std::string tf_frame)
Set the output TF frame the data should be transformed into after processing.
ros::Subscriber sub_input_
The input PointCloud subscriber.
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Subscriber sub_axis_
The input PointCloud subscriber.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
PointIndices indices_
Pointer to a set of indices stored internally. (used when latched_indices_ is set).
PointCloud::ConstPtr PointCloudConstPtr
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:72
pcl_msgs::PointIndices PointIndices
Definition: pcl_nodelet.h:81
message_filters::PassThrough< PointIndices > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
void setOutputTFframe(std::string tf_frame)
Set the output TF frame the data should be transformed into after processing.
std::string getOutputTFframe()
Get the TF frame the PointCloud should be transformed into after processing.
SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods...
message_filters::PassThrough< pcl_msgs::PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
pcl::SACSegmentationFromNormals< pcl::PointXYZ, pcl::Normal > impl_
The PCL implementation used.
void setInputTFframe(std::string tf_frame)
Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
ros::Publisher pub_indices_
The output PointIndices publisher.
SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models...
std::string tf_input_orig_frame_
The original data input TF frame.
void add(const MConstPtr &msg)
message_filters::Subscriber< PointCloudN > sub_normals_filter_
The normals PointCloud subscriber filter.
pcl::SACSegmentation< pcl::PointXYZ > impl_
The PCL implementation used.
PointCloudN::ConstPtr PointCloudNConstPtr
std::string getOutputTFframe()
Get the TF frame the PointCloud should be transformed into after processing.
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
void setInputTFframe(std::string tf_frame)
Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.
pcl::PointCloud< pcl::PointXYZ > PointCloud
void indices_callback(const PointIndicesConstPtr &indices)
Indices callback. Used when latched_indices_ is set.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_e_
virtual void onInit()
Nodelet initialization routine.
SACSegmentation()
Constructor.
pcl::PointCloud< pcl::Normal > PointCloudN
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_a_
Synchronized input, normals, and indices.
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationFromNormalsConfig > > srv_
Pointer to a dynamic reconfigure service.
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
std::string getInputTFframe()
Get the TF frame the input PointCloud should be transformed into before processing.
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
std::string getInputTFframe()
Get the TF frame the input PointCloud should be transformed into before processing.
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationConfig > > srv_
Pointer to a dynamic reconfigure service.


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