include
jsk_pcl_ros_utils
subtract_point_indices.h
Go to the documentation of this file.
1
// -*- mode: c++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2016, 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
37
#ifndef JSK_PCL_ROS_UTILS_SUBTRACT_POINT_INDICES_H_
38
#define JSK_PCL_ROS_UTILS_SUBTRACT_POINT_INDICES_H_
39
40
#include <jsk_topic_tools/diagnostic_nodelet.h>
41
42
#include "
jsk_recognition_utils/pcl_conversion_util.h
"
43
#include "
jsk_recognition_utils/pcl_util.h
"
44
45
#include <
message_filters/subscriber.h
>
46
#include <
message_filters/time_synchronizer.h
>
47
#include <
message_filters/synchronizer.h
>
48
#include <
message_filters/sync_policies/exact_time.h
>
49
#include <
message_filters/sync_policies/approximate_time.h
>
50
51
namespace
jsk_pcl_ros_utils
52
{
53
class
SubtractPointIndices:
public
jsk_topic_tools::DiagnosticNodelet
54
{
55
public
:
56
typedef
message_filters::sync_policies::ExactTime
<
57
PCLIndicesMsg
,
58
PCLIndicesMsg
>
SyncPolicy
;
59
typedef
message_filters::sync_policies::ApproximateTime
<
60
PCLIndicesMsg
,
61
PCLIndicesMsg
>
ASyncPolicy
;
62
63
SubtractPointIndices
(): DiagnosticNodelet(
"SubtractPointIndices"
) {}
64
virtual
~SubtractPointIndices
();
65
66
protected
:
67
virtual
void
onInit
();
68
virtual
void
subscribe
();
69
virtual
void
unsubscribe
();
70
virtual
void
subtract
(
71
const
PCLIndicesMsg::ConstPtr& src1,
72
const
PCLIndicesMsg::ConstPtr& src2);
73
74
ros::Publisher
pub_
;
75
message_filters::Subscriber<PCLIndicesMsg>
sub_src1_
;
76
message_filters::Subscriber<PCLIndicesMsg>
sub_src2_
;
77
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy>
>
sync_
;
78
boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy>
>
async_
;
79
bool
approximate_sync_
;
80
private
:
81
82
};
83
}
84
85
#endif
jsk_pcl_ros_utils
Definition:
add_point_indices.h:51
jsk_pcl_ros_utils::SubtractPointIndices::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition:
subtract_point_indices.h:141
ros::Publisher
boost::shared_ptr
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
time_synchronizer.h
message_filters::Subscriber< PCLIndicesMsg >
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::SubtractPointIndices::unsubscribe
virtual void unsubscribe()
Definition:
subtract_point_indices_nodelet.cpp:82
jsk_pcl_ros_utils::SubtractPointIndices::pub_
ros::Publisher pub_
Definition:
subtract_point_indices.h:138
jsk_pcl_ros_utils::SubtractPointIndices::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition:
subtract_point_indices.h:142
subscriber.h
jsk_pcl_ros_utils::SubtractPointIndices::subtract
virtual void subtract(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
Definition:
subtract_point_indices_nodelet.cpp:88
jsk_pcl_ros_utils::SubtractPointIndices::~SubtractPointIndices
virtual ~SubtractPointIndices()
Definition:
subtract_point_indices_nodelet.cpp:50
pcl_conversion_util.h
exact_time.h
pcl_util.h
jsk_pcl_ros_utils::SubtractPointIndices::onInit
virtual void onInit()
Definition:
subtract_point_indices_nodelet.cpp:42
jsk_pcl_ros_utils::SubtractPointIndices::approximate_sync_
bool approximate_sync_
Definition:
subtract_point_indices.h:143
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::SubtractPointIndices::subscribe
virtual void subscribe()
Definition:
subtract_point_indices_nodelet.cpp:62
message_filters::sync_policies::ExactTime
jsk_pcl_ros_utils::SubtractPointIndices::sub_src1_
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
Definition:
subtract_point_indices.h:139
jsk_pcl_ros_utils::SubtractPointIndices::sub_src2_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
Definition:
subtract_point_indices.h:140
jsk_pcl_ros_utils::SubtractPointIndices::SubtractPointIndices
SubtractPointIndices()
Definition:
subtract_point_indices.h:127
jsk_pcl_ros_utils::SubtractPointIndices::SyncPolicy
message_filters::sync_policies::ExactTime< PCLIndicesMsg, PCLIndicesMsg > SyncPolicy
Definition:
subtract_point_indices.h:122
jsk_pcl_ros_utils::SubtractPointIndices::ASyncPolicy
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, PCLIndicesMsg > ASyncPolicy
Definition:
subtract_point_indices.h:125
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43