pointcloud_to_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) 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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <cv_bridge/cv_bridge.h>
40 
41 namespace jsk_pcl_ros_utils
42 {
44  {
45  DiagnosticNodelet::onInit();
46  pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
47  onInitPostProcess();
48  }
49 
51  {
52  sub_ = pnh_->subscribe("input", 1, &PointCloudToPointIndices::convert, this);
53  }
54 
56  {
57  sub_.shutdown();
58  }
59 
60  void PointCloudToPointIndices::convert(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
61  {
62  vital_checker_->poke();
63  pcl::PointCloud<pcl::PointXYZ>::Ptr pc(new pcl::PointCloud<pcl::PointXYZ>);
64  pcl::fromROSMsg(*cloud_msg, *pc);
65  PCLIndicesMsg indices_msg;
66  for (size_t i = 0; i < pc->points.size(); i++)
67  {
68  if (!isnan(pc->points[i].x) && !isnan(pc->points[i].y) && !isnan(pc->points[i].z))
69  {
70  indices_msg.indices.push_back(i);
71  }
72  }
73  indices_msg.header = cloud_msg->header;
74  pub_.publish(indices_msg);
75  }
76 }
77 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
image_encodings.h
jsk_pcl_ros_utils::PointCloudToPointIndices::sub_
ros::Subscriber sub_
Definition: pointcloud_to_point_indices.h:125
i
int i
pointcloud_to_point_indices.h
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
ros::Subscriber::shutdown
void shutdown()
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros_utils::PointCloudToPointIndices::onInit
virtual void onInit()
Definition: pointcloud_to_point_indices_nodelet.cpp:43
class_list_macros.h
jsk_pcl_ros_utils::PointCloudToPointIndices::unsubscribe
virtual void unsubscribe()
Definition: pointcloud_to_point_indices_nodelet.cpp:55
jsk_pcl_ros_utils::PointCloudToPointIndices::convert
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &point_msg)
Definition: pointcloud_to_point_indices_nodelet.cpp:60
pcl_conversion_util.h
jsk_pcl_ros_utils::PointCloudToPointIndices::pub_
ros::Publisher pub_
Definition: pointcloud_to_point_indices.h:126
nodelet::Nodelet
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudToPointIndices, nodelet::Nodelet)
jsk_pcl_ros_utils::PointCloudToPointIndices::subscribe
virtual void subscribe()
Definition: pointcloud_to_point_indices_nodelet.cpp:50
cv_bridge.h
jsk_pcl_ros_utils::PointCloudToPointIndices
Definition: pointcloud_to_point_indices.h:77


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