mask_image_cluster_filter_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/mask_image_cluster_filter.h"
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <image_geometry/pinhole_camera_model.h>
00040 #include "jsk_recognition_utils/pcl_conversion_util.h"
00041 #include <sensor_msgs/image_encodings.h>
00042 #include <pcl/filters/extract_indices.h>
00043 
00044 
00045 namespace jsk_pcl_ros
00046 {
00047   void MaskImageClusterFilter::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     pub_ = advertise<PCLIndicesMsg>(
00051       *pnh_, "output", 1);
00052     onInitPostProcess();
00053   }
00054 
00055   void MaskImageClusterFilter::subscribe()
00056   {
00057     sub_image_ = pnh_->subscribe("input/mask", 1,
00058                                  &MaskImageClusterFilter::imageCalback, this);
00059     sub_info_ = pnh_->subscribe("input/camera_info", 1,
00060                                 &MaskImageClusterFilter::infoCalback, this);
00061     sub_input_.subscribe(*pnh_, "input", 1);
00062     sub_target_.subscribe(*pnh_, "target", 1); 
00063     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00064     sync_->connectInput(sub_input_, sub_target_);
00065     sync_->registerCallback(boost::bind(&MaskImageClusterFilter::concat, this, _1, _2));
00066   }
00067   
00068   void MaskImageClusterFilter::unsubscribe()
00069   {
00070     sub_image_.shutdown();
00071     sub_info_.shutdown();
00072     sub_input_.unsubscribe();
00073     sub_target_.unsubscribe();
00074   }
00075   
00076   void MaskImageClusterFilter::infoCalback(
00077     const sensor_msgs::CameraInfo::ConstPtr& info_ms)
00078   {
00079     boost::mutex::scoped_lock lock(mutex_);
00080     camera_info_ = info_ms;
00081   }
00082 
00083   void MaskImageClusterFilter::imageCalback(
00084     const sensor_msgs::Image::ConstPtr& mask_msg)
00085   {
00086     boost::mutex::scoped_lock lock(mutex_);
00087     cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00088       mask_msg, sensor_msgs::image_encodings::MONO8);
00089     mask_image_ = cv_ptr->image;
00090   }
00091 
00092   void MaskImageClusterFilter::concat(
00093     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00094     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
00095   {
00096     boost::mutex::scoped_lock lock(mutex_);
00097     if (camera_info_ && !mask_image_.empty()) {
00098       image_geometry::PinholeCameraModel model;
00099       model.fromCameraInfo(camera_info_);
00100       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud
00101         (new pcl::PointCloud<pcl::PointXYZRGB>);
00102       pcl::fromROSMsg(*cloud_msg, *cloud);
00103       PCLIndicesMsg indices;
00104       indices.header = cloud_msg->header;
00105       pcl::ExtractIndices<pcl::PointXYZRGB> extract;
00106       extract.setInputCloud(cloud);
00107       for (size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
00108         pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00109         pcl::IndicesPtr vindices;
00110         vindices.reset (new std::vector<int> (indices_input->cluster_indices[i].indices));
00111         extract.setIndices(vindices);
00112         extract.filter(*segmented_cloud);
00113         bool in_mask = false;
00114         for (size_t j = 0; j < segmented_cloud->points.size(); j++) {
00115           pcl::PointXYZRGB p = segmented_cloud->points[j];
00116           cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00117           // check size
00118           if (uv.x > 0 && uv.x < mask_image_.cols &&
00119               uv.y > 0 && uv.y < mask_image_.rows) {
00120             if (mask_image_.at<uchar>(uv.y, uv.x) == 255) {
00121               in_mask = true;
00122               break;
00123             }
00124           }
00125         }
00126         if (in_mask) {
00127           vindices->size();
00128           for(size_t j=0; j < vindices->size(); j++)
00129             {
00130               indices.indices.push_back((*vindices)[j]);
00131             }
00132         }
00133       }
00134       pub_.publish(indices);
00135     }
00136   }
00137 }
00138 
00139 #include <pluginlib/class_list_macros.h>
00140 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MaskImageClusterFilter, nodelet::Nodelet);
00141 
00142 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50