include
pcl_ros
segmentation
extract_clusters.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: extract_clusters.h 35361 2011-01-20 04:34:49Z rusu $
35
*
36
*/
37
38
#ifndef PCL_ROS_EXTRACT_CLUSTERS_H_
39
#define PCL_ROS_EXTRACT_CLUSTERS_H_
40
41
#include <pcl/segmentation/extract_clusters.h>
42
#include "
pcl_ros/pcl_nodelet.h
"
43
44
// Dynamic reconfigure
45
#include <dynamic_reconfigure/server.h>
46
#include "pcl_ros/EuclideanClusterExtractionConfig.h"
47
48
namespace
pcl_ros
49
{
50
namespace
sync_policies
=
message_filters::sync_policies
;
51
54
57
class
EuclideanClusterExtraction
:
public
PCLNodelet
58
{
59
public
:
61
EuclideanClusterExtraction
() :
publish_indices_
(false),
max_clusters_
(
std
::numeric_limits<int>::max ()) {};
62
63
protected
:
64
// ROS nodelet attributes
66
bool
publish_indices_
;
67
69
int
max_clusters_
;
70
72
boost::shared_ptr<dynamic_reconfigure::Server<EuclideanClusterExtractionConfig>
>
srv_
;
73
75
void
onInit
();
76
78
void
subscribe
();
79
void
unsubscribe
();
80
85
void
config_callback
(EuclideanClusterExtractionConfig &config, uint32_t level);
86
91
void
input_indices_callback
(
const
PointCloudConstPtr
&cloud,
const
PointIndicesConstPtr
&indices);
92
93
private
:
95
pcl::EuclideanClusterExtraction<pcl::PointXYZ>
impl_
;
96
98
ros::Subscriber
sub_input_
;
99
101
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices>
> >
sync_input_indices_e_
;
102
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices>
> >
sync_input_indices_a_
;
103
104
public
:
105
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
106
};
107
}
108
109
#endif //#ifndef PCL_ROS_EXTRACT_CLUSTERS_H_
pcl_ros::EuclideanClusterExtraction::publish_indices_
bool publish_indices_
Publish indices or convert to PointCloud clusters. Default: false.
Definition:
extract_clusters.h:61
pcl_ros::EuclideanClusterExtraction::srv_
boost::shared_ptr< dynamic_reconfigure::Server< EuclideanClusterExtractionConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition:
extract_clusters.h:72
pcl_ros
Definition:
boundary.h:46
pcl_nodelet.h
std
pcl_ros::EuclideanClusterExtraction::subscribe
void subscribe()
LazyNodelet connection routine.
Definition:
extract_clusters.cpp:98
pcl_ros::EuclideanClusterExtraction::unsubscribe
void unsubscribe()
Definition:
extract_clusters.cpp:127
pcl_ros::EuclideanClusterExtraction::sync_input_indices_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointIndices > > > sync_input_indices_a_
Definition:
extract_clusters.h:102
boost::shared_ptr
pcl_ros::EuclideanClusterExtraction::sync_input_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
Definition:
extract_clusters.h:101
ros::Subscriber
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::EuclideanClusterExtraction
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sen...
Definition:
extract_clusters.h:57
pcl_ros::EuclideanClusterExtraction::max_clusters_
int max_clusters_
Maximum number of clusters to publish.
Definition:
extract_clusters.h:69
pcl_ros::EuclideanClusterExtraction::EuclideanClusterExtraction
EuclideanClusterExtraction()
Empty constructor.
Definition:
extract_clusters.h:61
pcl_ros::EuclideanClusterExtraction::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition:
extract_clusters.h:98
pcl_ros::EuclideanClusterExtraction::onInit
void onInit()
Nodelet initialization routine.
Definition:
extract_clusters.cpp:50
message_filters::sync_policies
pcl_ros::EuclideanClusterExtraction::impl_
pcl::EuclideanClusterExtraction< pcl::PointXYZ > impl_
The PCL implementation used.
Definition:
extract_clusters.h:95
pcl_ros::EuclideanClusterExtraction::input_indices_callback
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
Definition:
extract_clusters.cpp:166
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition:
pcl_nodelet.h:84
pcl_ros::EuclideanClusterExtraction::config_callback
void config_callback(EuclideanClusterExtractionConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition:
extract_clusters.cpp:140
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Thu Feb 16 2023 03:08:02