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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48