mask_image_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_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 
00043 namespace jsk_pcl_ros
00044 {
00045   void MaskImageFilter::onInit()
00046   {
00047     DiagnosticNodelet::onInit();
00048     pnh_->param("negative", negative_, false);
00049     pub_ = advertise<PCLIndicesMsg>(
00050       *pnh_, "output", 1);
00051     DiagnosticNodelet::onInitPostProcess();
00052   }
00053 
00054   void MaskImageFilter::subscribe()
00055   {
00056     sub_cloud_ = pnh_->subscribe("input", 1, &MaskImageFilter::filter, this);
00057     sub_image_ = pnh_->subscribe("input/mask", 1,
00058                                  &MaskImageFilter::imageCalback, this);
00059     sub_info_ = pnh_->subscribe("input/camera_info", 1,
00060                                 &MaskImageFilter::infoCalback, this);
00061   }
00062 
00063   void MaskImageFilter::unsubscribe()
00064   {
00065     sub_cloud_.shutdown();
00066     sub_info_.shutdown();
00067     sub_info_.shutdown();
00068   }
00069   
00070   void MaskImageFilter::infoCalback(
00071     const sensor_msgs::CameraInfo::ConstPtr& info_ms)
00072   {
00073     boost::mutex::scoped_lock lock(mutex_);
00074     camera_info_ = info_ms;
00075   }
00076 
00077   void MaskImageFilter::imageCalback(
00078     const sensor_msgs::Image::ConstPtr& mask_msg)
00079   {
00080     boost::mutex::scoped_lock lock(mutex_);
00081     cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00082       mask_msg, sensor_msgs::image_encodings::MONO8);
00083     mask_image_ = cv_ptr->image;
00084 
00085     if (negative_) {
00086       cv::bitwise_not(mask_image_, mask_image_);
00087     }
00088   }
00089 
00090   void MaskImageFilter::filter(
00091     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00092   {
00093     boost::mutex::scoped_lock lock(mutex_);
00094     if (camera_info_ && !mask_image_.empty()) {
00095       image_geometry::PinholeCameraModel model;
00096       model.fromCameraInfo(camera_info_);
00097       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00098         (new pcl::PointCloud<pcl::PointXYZ>);
00099       pcl::fromROSMsg(*cloud_msg, *cloud);
00100       PCLIndicesMsg indices;
00101       indices.header = cloud_msg->header;
00102       for (size_t i = 0; i < cloud->points.size(); i++) {
00103         pcl::PointXYZ p = cloud->points[i];
00104         cv::Point2d uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00105         // check size
00106         if (uv.x > 0 && uv.x < mask_image_.cols &&
00107             uv.y > 0 && uv.y < mask_image_.rows) {
00108           if (mask_image_.at<uchar>(uv.y, uv.x) == 255) {
00109             indices.indices.push_back(i);
00110           }
00111         }
00112       }
00113       pub_.publish(indices);
00114     }
00115   }
00116 }
00117 
00118 #include <pluginlib/class_list_macros.h>
00119 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MaskImageFilter, nodelet::Nodelet);
00120 
00121 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43