add_point_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 
37 #ifndef JSK_PERCEPTION_ADD_POINT_INDICES_H_
38 #define JSK_PERCEPTION_ADD_POINT_INDICES_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 
44 
50 
52 {
53  class AddPointIndices: public jsk_topic_tools::DiagnosticNodelet
54  {
55  public:
62 
63  AddPointIndices(): DiagnosticNodelet("AddPointIndices") {}
64  virtual ~AddPointIndices();
65 
66  protected:
67  virtual void onInit();
68  virtual void subscribe();
69  virtual void unsubscribe();
70  virtual void add(
71  const PCLIndicesMsg::ConstPtr& src1,
72  const PCLIndicesMsg::ConstPtr& src2);
73 
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::AddPointIndices::ASyncPolicy
message_filters::sync_policies::ApproximateTime< PCLIndicesMsg, PCLIndicesMsg > ASyncPolicy
Definition: add_point_indices.h:125
ros::Publisher
boost::shared_ptr
src2
src2
jsk_pcl_ros_utils::AddPointIndices::subscribe
virtual void subscribe()
Definition: add_point_indices_nodelet.cpp:62
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros_utils::AddPointIndices::onInit
virtual void onInit()
Definition: add_point_indices_nodelet.cpp:42
time_synchronizer.h
jsk_pcl_ros_utils::AddPointIndices
Definition: add_point_indices.h:85
jsk_pcl_ros_utils::AddPointIndices::add
virtual void add(const PCLIndicesMsg::ConstPtr &src1, const PCLIndicesMsg::ConstPtr &src2)
Definition: add_point_indices_nodelet.cpp:88
message_filters::Subscriber< PCLIndicesMsg >
jsk_pcl_ros_utils::AddPointIndices::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: add_point_indices.h:142
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::AddPointIndices::AddPointIndices
AddPointIndices()
Definition: add_point_indices.h:127
subscriber.h
jsk_pcl_ros_utils::AddPointIndices::SyncPolicy
message_filters::sync_policies::ExactTime< PCLIndicesMsg, PCLIndicesMsg > SyncPolicy
Definition: add_point_indices.h:122
jsk_pcl_ros_utils::AddPointIndices::unsubscribe
virtual void unsubscribe()
Definition: add_point_indices_nodelet.cpp:82
pcl_conversion_util.h
jsk_pcl_ros_utils::AddPointIndices::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: add_point_indices.h:141
src1
src1
exact_time.h
jsk_pcl_ros_utils::AddPointIndices::sub_src1_
message_filters::Subscriber< PCLIndicesMsg > sub_src1_
Definition: add_point_indices.h:139
pcl_util.h
jsk_pcl_ros_utils::AddPointIndices::approximate_sync_
bool approximate_sync_
Definition: add_point_indices.h:143
jsk_pcl_ros_utils::AddPointIndices::sub_src2_
message_filters::Subscriber< PCLIndicesMsg > sub_src2_
Definition: add_point_indices.h:140
synchronizer.h
approximate_time.h
jsk_pcl_ros_utils::AddPointIndices::pub_
ros::Publisher pub_
Definition: add_point_indices.h:138
jsk_pcl_ros_utils::AddPointIndices::~AddPointIndices
virtual ~AddPointIndices()
Definition: add_point_indices_nodelet.cpp:50
message_filters::sync_policies::ExactTime


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43