segment_differences.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: segment_differences.h 35361 2011-01-20 04:34:49Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_SEGMENT_DIFFERENCES_H_
39 #define PCL_ROS_SEGMENT_DIFFERENCES_H_
40 
41 #include <pcl/segmentation/segment_differences.h>
42 #include "pcl_ros/pcl_nodelet.h"
43 
44 // Dynamic reconfigure
45 #include <dynamic_reconfigure/server.h>
46 #include "pcl_ros/SegmentDifferencesConfig.h"
47 
48 
49 namespace pcl_ros
50 {
52 
56 
61  {
62  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
65 
66  public:
69 
70  protected:
73 
77 
80 
82  void onInit ();
83 
85  void subscribe ();
86  void unsubscribe ();
87 
92  void config_callback (SegmentDifferencesConfig &config, uint32_t level);
93 
98  void input_target_callback (const PointCloudConstPtr &cloud,
99  const PointCloudConstPtr &cloud_target);
100 
101  private:
103  pcl::SegmentDifferences<pcl::PointXYZ> impl_;
104 
105  public:
106  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
107  };
108 }
109 
110 #endif //#ifndef PCL_ROS_SEGMENT_DIFFERENCES_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::SegmentDifferences::unsubscribe
void unsubscribe()
Definition: segment_differences.cpp:87
boost::shared_ptr
pcl_ros::SegmentDifferences::PointCloudPtr
boost::shared_ptr< PointCloud > PointCloudPtr
Definition: segment_differences.h:63
pcl_ros
Definition: boundary.h:46
pcl_ros::SegmentDifferences::PointCloudConstPtr
boost::shared_ptr< const PointCloud > PointCloudConstPtr
Definition: segment_differences.h:64
pcl_nodelet.h
message_filters::Subscriber< PointCloud >
pcl_ros::SegmentDifferences::sub_target_filter_
message_filters::Subscriber< PointCloud > sub_target_filter_
The message filter subscriber for PointCloud2.
Definition: segment_differences.h:68
pcl_ros::SegmentDifferences::SegmentDifferences
SegmentDifferences()
Empty constructor.
Definition: segment_differences.h:68
pcl_ros::SegmentDifferences::PointCloud
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: segment_differences.h:62
pcl_ros::SegmentDifferences::onInit
void onInit()
Nodelet initialization routine.
Definition: segment_differences.cpp:43
message_filters::sync_policies
pcl_ros::SegmentDifferences::input_target_callback
void input_target_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &cloud_target)
Input point cloud callback.
Definition: segment_differences.cpp:107
pcl_ros::SegmentDifferences::sync_input_target_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud > > > sync_input_target_a_
Definition: segment_differences.h:76
pcl_ros::SegmentDifferences::srv_
boost::shared_ptr< dynamic_reconfigure::Server< SegmentDifferencesConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: segment_differences.h:79
pcl_ros::SegmentDifferences::impl_
pcl::SegmentDifferences< pcl::PointXYZ > impl_
The PCL implementation used.
Definition: segment_differences.h:103
pcl_ros::SegmentDifferences::subscribe
void subscribe()
LazyNodelet connection routine.
Definition: segment_differences.cpp:60
pcl_ros::SegmentDifferences::config_callback
void config_callback(SegmentDifferencesConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition: segment_differences.cpp:95
pcl_ros::SegmentDifferences
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the ...
Definition: segment_differences.h:60
pcl_ros::SegmentDifferences::sync_input_target_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud > > > sync_input_target_e_
Synchronized input, and planar hull.
Definition: segment_differences.h:75


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