00001 // -*- mode: c++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2014, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 #include "jsk_pcl_ros_utils/pointcloud_to_cluster_point_indices.h" 00037 00038 namespace jsk_pcl_ros_utils 00039 { 00040 void PointCloudToClusterPointIndices::onInit() 00041 { 00042 DiagnosticNodelet::onInit(); 00043 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1); 00044 onInitPostProcess(); 00045 } 00046 00047 void PointCloudToClusterPointIndices::subscribe() 00048 { 00049 sub_ = pnh_->subscribe( 00050 "input", 1, &PointCloudToClusterPointIndices::convert, this); 00051 } 00052 00053 void PointCloudToClusterPointIndices::unsubscribe() 00054 { 00055 sub_.shutdown(); 00056 } 00057 00058 void PointCloudToClusterPointIndices::convert( 00059 const sensor_msgs::PointCloud2::ConstPtr& msg) 00060 { 00061 vital_checker_->poke(); 00062 int point_num = msg->width * msg->height; 00063 pcl_msgs::PointIndices indices; 00064 jsk_recognition_msgs::ClusterPointIndices cluster_indices; 00065 for (int i = 0; i < point_num; i++) { 00066 indices.indices.push_back(i); 00067 } 00068 indices.header = msg->header; 00069 cluster_indices.header = msg->header; 00070 cluster_indices.cluster_indices.push_back(indices); 00071 pub_.publish(cluster_indices); 00072 } 00073 } 00074 00075 #include <pluginlib/class_list_macros.h> 00076 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PointCloudToClusterPointIndices, 00077 nodelet::Nodelet); 00078