pointcloud_to_cluster_point_indices_nodelet.cpp
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 
37 
38 #include <pcl/point_cloud.h>
39 #include <pcl/point_types.h>
41 
42 namespace jsk_pcl_ros_utils
43 {
45  {
46  DiagnosticNodelet::onInit();
47  pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
48  pnh_->param<bool>("skip_nan", skip_nan_, false);
50  }
51 
53  {
54  sub_ = pnh_->subscribe(
55  "input", 1, &PointCloudToClusterPointIndices::convert, this);
56  }
57 
59  {
60  sub_.shutdown();
61  }
62 
64  const sensor_msgs::PointCloud2::ConstPtr& msg)
65  {
66  vital_checker_->poke();
67  pcl::PointCloud<pcl::PointXYZRGB> cloud;
68  pcl::fromROSMsg(*msg, cloud);
69  int point_num = msg->width * msg->height;
70  pcl_msgs::PointIndices indices;
71  jsk_recognition_msgs::ClusterPointIndices cluster_indices;
72  for (int i = 0; i < point_num; i++) {
73  if (skip_nan_ &&
74  (std::isnan(cloud.points[i].x) || std::isnan(cloud.points[i].y) || std::isnan(cloud.points[i].z)))
75  {
76  continue;
77  }
78  indices.indices.push_back(i);
79  }
80  indices.header = msg->header;
81  cluster_indices.header = msg->header;
82  cluster_indices.cluster_indices.push_back(indices);
83  pub_.publish(cluster_indices);
84  }
85 }
86 
90 
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudToClusterPointIndices, nodelet::Nodelet)
jsk_topic_tools::VitalChecker::Ptr vital_checker_


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15