include
jsk_pcl_ros
extract_indices.h
Go to the documentation of this file.
1
// -*- mode: c++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2015, JSK Lab
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/or other materials provided
17
* with the distribution.
18
* * Neither the name of the JSK Lab nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
36
#ifndef JSK_PCL_ROS_EXTRACT_INDICES_H_
37
#define JSK_PCL_ROS_EXTRACT_INDICES_H_
38
39
#include "jsk_topic_tools/diagnostic_nodelet.h"
40
#include "
jsk_recognition_utils/pcl_conversion_util.h
"
41
42
#include <sensor_msgs/PointCloud2.h>
43
#include <
message_filters/subscriber.h
>
44
#include <
message_filters/sync_policies/exact_time.h
>
45
#include <
message_filters/sync_policies/approximate_time.h
>
46
47
48
namespace
jsk_pcl_ros
49
{
50
class
ExtractIndices
:
public
jsk_topic_tools::DiagnosticNodelet
51
{
52
public
:
53
typedef
message_filters::sync_policies::ExactTime
<
54
PCLIndicesMsg
,
55
sensor_msgs::PointCloud2 >
SyncPolicy
;
56
typedef
message_filters::sync_policies::ApproximateTime
<
57
PCLIndicesMsg
,
58
sensor_msgs::PointCloud2 >
ApproximateSyncPolicy
;
59
60
ExtractIndices
(): DiagnosticNodelet(
"ExtractIndices"
) {}
61
virtual
~ExtractIndices
();
62
protected
:
63
virtual
void
onInit
();
64
virtual
void
subscribe
();
65
virtual
void
unsubscribe
();
66
virtual
void
convert
(
67
const
PCLIndicesMsg::ConstPtr& indices_msg,
68
const
sensor_msgs::PointCloud2::ConstPtr&
msg
);
69
70
bool
keep_organized_
;
71
bool
negative_
;
72
int
max_queue_size_
;
73
bool
approximate_sync_
;
74
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy>
>
sync_
;
75
boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy>
>
async_
;
76
ros::Publisher
pub_
;
77
message_filters::Subscriber<sensor_msgs::PointCloud2>
sub_cloud_
;
78
message_filters::Subscriber<PCLIndicesMsg>
sub_indices_
;
79
private
:
80
};
81
82
}
83
84
#endif
pcl_ros::ExtractIndices
jsk_pcl_ros::ExtractIndices::unsubscribe
virtual void unsubscribe()
Definition:
extract_indices_nodelet.cpp:91
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::ExtractIndices::pub_
ros::Publisher pub_
Definition:
extract_indices.h:140
jsk_pcl_ros::ExtractIndices::onInit
virtual void onInit()
Definition:
extract_indices_nodelet.cpp:50
jsk_pcl_ros::ExtractIndices::SyncPolicy
message_filters::sync_policies::ExactTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > SyncPolicy
Definition:
extract_indices.h:119
jsk_pcl_ros::ExtractIndices::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition:
extract_indices.h:138
jsk_pcl_ros::ExtractIndices::sub_indices_
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
Definition:
extract_indices.h:142
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros::ExtractIndices::negative_
bool negative_
Definition:
extract_indices.h:135
jsk_pcl_ros::ExtractIndices::convert
virtual void convert(const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition:
extract_indices_nodelet.cpp:97
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::ExtractIndices::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition:
extract_indices.h:141
jsk_pcl_ros::ExtractIndices::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition:
extract_indices.h:139
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros
Definition:
add_color_from_image.h:51
subscriber.h
jsk_pcl_ros::ExtractIndices::approximate_sync_
bool approximate_sync_
Definition:
extract_indices.h:137
pcl_conversion_util.h
exact_time.h
jsk_pcl_ros::ExtractIndices::subscribe
virtual void subscribe()
Definition:
extract_indices_nodelet.cpp:73
jsk_pcl_ros::ExtractIndices::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
Definition:
extract_indices.h:122
jsk_pcl_ros::ExtractIndices::max_queue_size_
int max_queue_size_
Definition:
extract_indices.h:136
jsk_pcl_ros::ExtractIndices::keep_organized_
bool keep_organized_
Definition:
extract_indices.h:134
approximate_time.h
message_filters::sync_policies::ExactTime
jsk_pcl_ros::ExtractIndices::ExtractIndices
ExtractIndices()
Definition:
extract_indices.h:124
pose_with_covariance_sample.msg
msg
Definition:
pose_with_covariance_sample.py:22
jsk_pcl_ros::ExtractIndices::~ExtractIndices
virtual ~ExtractIndices()
Definition:
extract_indices_nodelet.cpp:61
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44