include
pcl_ros
segmentation
extract_polygonal_prism_data.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_polygonal_prism_data.h 35361 2011-01-20 04:34:49Z rusu $
35
*
36
*/
37
38
#ifndef PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
39
#define PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
40
41
#include "
pcl_ros/pcl_nodelet.h
"
42
#include <
message_filters/sync_policies/exact_time.h
>
43
#include <
message_filters/sync_policies/approximate_time.h
>
44
#include <
message_filters/pass_through.h
>
45
46
// PCL includes
47
#include <pcl/segmentation/extract_polygonal_prism_data.h>
48
49
// Dynamic reconfigure
50
#include <dynamic_reconfigure/server.h>
51
#include "pcl_ros/ExtractPolygonalPrismDataConfig.h"
52
53
namespace
pcl_ros
54
{
55
namespace
sync_policies
=
message_filters::sync_policies
;
56
64
class
ExtractPolygonalPrismData
:
public
PCLNodelet
65
{
66
typedef
pcl::PointCloud<pcl::PointXYZ>
PointCloud
;
67
typedef
boost::shared_ptr<PointCloud>
PointCloudPtr
;
68
typedef
boost::shared_ptr<const PointCloud>
PointCloudConstPtr
;
69
70
protected
:
72
ros::Publisher
pub_output_
;
73
75
message_filters::Subscriber<PointCloud>
sub_hull_filter_
;
76
78
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices>
> >
sync_input_hull_indices_e_
;
79
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices>
> >
sync_input_hull_indices_a_
;
80
82
boost::shared_ptr<dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>
>
srv_
;
83
86
message_filters::PassThrough<PointIndices>
nf_
;
87
92
inline
void
93
input_callback
(
const
PointCloudConstPtr
&input)
94
{
95
PointIndices
cloud;
96
cloud.header.stamp =
pcl_conversions::fromPCL
(input->header).stamp;
97
nf_
.
add
(boost::make_shared<PointIndices> (cloud));
98
}
99
101
void
onInit
();
102
104
void
subscribe
();
105
void
unsubscribe
();
106
111
void
config_callback
(ExtractPolygonalPrismDataConfig &config, uint32_t level);
112
118
void
input_hull_indices_callback
(
const
PointCloudConstPtr
&cloud,
119
const
PointCloudConstPtr
&hull,
120
const
PointIndicesConstPtr
&indices);
121
122
private
:
124
pcl::ExtractPolygonalPrismData<pcl::PointXYZ>
impl_
;
125
public
:
126
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
127
};
128
}
129
130
#endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_
PointCloudConstPtr
PointCloud::ConstPtr PointCloudConstPtr
Definition:
bag_to_pcd.cpp:57
ros::Publisher
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition:
pcl_nodelet.h:73
pass_through.h
boost::shared_ptr
pcl_ros
Definition:
boundary.h:46
pcl_ros::ExtractPolygonalPrismData::unsubscribe
void unsubscribe()
Definition:
extract_polygonal_prism_data.cpp:104
pcl_ros::ExtractPolygonalPrismData::onInit
void onInit()
Nodelet initialization routine.
Definition:
extract_polygonal_prism_data.cpp:49
pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_e_
Synchronized input, planar hull, and indices.
Definition:
extract_polygonal_prism_data.h:78
pcl_ros::ExtractPolygonalPrismData::impl_
pcl::ExtractPolygonalPrismData< pcl::PointXYZ > impl_
The PCL implementation used.
Definition:
extract_polygonal_prism_data.h:124
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition:
pcl_nodelet.h:84
pcl_nodelet.h
message_filters::Subscriber< PointCloud >
pcl_ros::ExtractPolygonalPrismData::PointCloudConstPtr
boost::shared_ptr< const PointCloud > PointCloudConstPtr
Definition:
extract_polygonal_prism_data.h:68
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
pcl_ros::ExtractPolygonalPrismData::sub_hull_filter_
message_filters::Subscriber< PointCloud > sub_hull_filter_
The message filter subscriber for PointCloud2.
Definition:
extract_polygonal_prism_data.h:75
pcl_ros::ExtractPolygonalPrismData::PointCloud
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition:
extract_polygonal_prism_data.h:66
pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_a_
Definition:
extract_polygonal_prism_data.h:79
pcl_ros::ExtractPolygonalPrismData::PointCloudPtr
boost::shared_ptr< PointCloud > PointCloudPtr
Definition:
extract_polygonal_prism_data.h:67
message_filters::PassThrough::add
void add(const EventType &evt)
pcl_ros::ExtractPolygonalPrismData::pub_output_
ros::Publisher pub_output_
The output PointIndices publisher.
Definition:
extract_polygonal_prism_data.h:72
exact_time.h
pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback
void input_hull_indices_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
Definition:
extract_polygonal_prism_data.cpp:135
pcl_ros::ExtractPolygonalPrismData::srv_
boost::shared_ptr< dynamic_reconfigure::Server< ExtractPolygonalPrismDataConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition:
extract_polygonal_prism_data.h:82
message_filters::sync_policies
pcl_ros::ExtractPolygonalPrismData::input_callback
void input_callback(const PointCloudConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Definition:
extract_polygonal_prism_data.h:93
message_filters::PassThrough< PointIndices >
approximate_time.h
pcl_ros::ExtractPolygonalPrismData::nf_
message_filters::PassThrough< PointIndices > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition:
extract_polygonal_prism_data.h:86
pcl_ros::PCLNodelet::PointIndices
pcl_msgs::PointIndices PointIndices
Definition:
pcl_nodelet.h:82
pcl_ros::ExtractPolygonalPrismData::subscribe
void subscribe()
LazyNodelet connection routine.
Definition:
extract_polygonal_prism_data.cpp:67
pcl_ros::ExtractPolygonalPrismData::config_callback
void config_callback(ExtractPolygonalPrismDataConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition:
extract_polygonal_prism_data.cpp:115
pcl_ros::ExtractPolygonalPrismData
ExtractPolygonalPrismData uses a set of point indices that represent a planar model,...
Definition:
extract_polygonal_prism_data.h:64
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40