Main Page
Namespaces
Classes
Files
File List
File Members
include
jsk_pcl_ros_utils
pointcloud_to_cluster_point_indices.h
Go to the documentation of this file.
1
// -*- mode: c++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2014, 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/o2r 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_UTILS_POINTCLOUD_TO_CLUSTER_POINT_INDICES_H_
37
#define JSK_PCL_ROS_UTILS_POINTCLOUD_TO_CLUSTER_POINT_INDICES_H_
38
39
#include <
jsk_topic_tools/diagnostic_nodelet.h
>
40
#include <jsk_recognition_msgs/ClusterPointIndices.h>
41
#include <sensor_msgs/PointCloud2.h>
42
43
namespace
jsk_pcl_ros_utils
44
{
45
class
PointCloudToClusterPointIndices
:
public
jsk_topic_tools::DiagnosticNodelet
46
{
47
public
:
48
PointCloudToClusterPointIndices
():
DiagnosticNodelet
(
"PointCloudToClusterPointIndices"
) {}
49
protected
:
50
virtual
void
onInit
();
51
virtual
void
subscribe
();
52
virtual
void
unsubscribe
();
53
virtual
void
convert
(
const
sensor_msgs::PointCloud2::ConstPtr&
msg
);
54
55
ros::Subscriber
sub_
;
56
ros::Publisher
pub_
;
57
58
bool
skip_nan_
;
59
60
private
:
61
};
62
63
}
64
65
#endif
msg
msg
jsk_pcl_ros_utils::PointCloudToClusterPointIndices
Definition:
pointcloud_to_cluster_point_indices.h:45
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::pub_
ros::Publisher pub_
Definition:
pointcloud_to_cluster_point_indices.h:56
diagnostic_nodelet.h
jsk_topic_tools::DiagnosticNodelet::DiagnosticNodelet
DiagnosticNodelet(const std::string &name)
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::subscribe
virtual void subscribe()
Definition:
pointcloud_to_cluster_point_indices_nodelet.cpp:52
ros::Subscriber
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::skip_nan_
bool skip_nan_
Definition:
pointcloud_to_cluster_point_indices.h:58
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::convert
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition:
pointcloud_to_cluster_point_indices_nodelet.cpp:63
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::sub_
ros::Subscriber sub_
Definition:
pointcloud_to_cluster_point_indices.h:55
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::PointCloudToClusterPointIndices
PointCloudToClusterPointIndices()
Definition:
pointcloud_to_cluster_point_indices.h:48
jsk_pcl_ros_utils
Definition:
add_point_indices.h:51
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::onInit
virtual void onInit()
Definition:
pointcloud_to_cluster_point_indices_nodelet.cpp:44
jsk_pcl_ros_utils::PointCloudToClusterPointIndices::unsubscribe
virtual void unsubscribe()
Definition:
pointcloud_to_cluster_point_indices_nodelet.cpp:58
ros::Publisher
jsk_topic_tools::DiagnosticNodelet
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15