apply_mask_image.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 #include "jsk_perception/apply_mask_image.h"
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <opencv2/opencv.hpp>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include "jsk_perception/image_utils.h"
00041 
00042 namespace jsk_perception
00043 {
00044   void ApplyMaskImage::onInit()
00045   {
00046     DiagnosticNodelet::onInit();
00047     pnh_->param("approximate_sync", approximate_sync_, false);
00048     pnh_->param("mask_black_to_transparent", mask_black_to_transparent_, false);
00049     pub_image_ = advertise<sensor_msgs::Image>(
00050       *pnh_, "output", 1);
00051     pub_mask_ = advertise<sensor_msgs::Image>(
00052       *pnh_, "output/mask", 1);
00053   }
00054 
00055   void ApplyMaskImage::subscribe()
00056   {
00057     sub_image_.subscribe(*pnh_, "input", 1);
00058     sub_mask_.subscribe(*pnh_, "input/mask", 1);
00059     if (approximate_sync_) {
00060       async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
00061       async_->connectInput(sub_image_, sub_mask_);
00062       async_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
00063     }
00064     else {
00065       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00066       sync_->connectInput(sub_image_, sub_mask_);
00067       sync_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
00068     }
00069   }
00070 
00071   void ApplyMaskImage::unsubscribe()
00072   {
00073     sub_image_.unsubscribe();
00074     sub_mask_.unsubscribe();
00075   }
00076 
00077   void ApplyMaskImage::apply(
00078     const sensor_msgs::Image::ConstPtr& image_msg,
00079     const sensor_msgs::Image::ConstPtr& mask_msg)
00080   {
00081     vital_checker_->poke();
00082     cv::Mat image;
00083     if (isBGRA(image_msg->encoding)) {
00084       cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00085       cv::cvtColor(tmp_image, image, cv::COLOR_BGRA2BGR);
00086     }
00087     else if (isRGBA(image_msg->encoding)) {
00088       cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00089       cv::cvtColor(tmp_image, image, cv::COLOR_RGBA2BGR);
00090     }
00091     else {  // BGR, RGB or GRAY
00092       image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00093     }
00094     cv::Mat mask = cv_bridge::toCvShare(mask_msg, "mono8")->image;
00095     if (image.cols != mask.cols || image.rows != mask.rows) {
00096       JSK_NODELET_ERROR("size of image and mask is different");
00097       JSK_NODELET_ERROR("image: %dx%dx", image.cols, image.rows);
00098       JSK_NODELET_ERROR("mask: %dx%dx", mask.cols, mask.rows);
00099       return;
00100     }
00101     
00102     cv::Rect region = boundingRectOfMaskImage(mask);
00103     cv::Mat clipped_mask = mask(region);
00104     pub_mask_.publish(cv_bridge::CvImage(
00105                         mask_msg->header,
00106                         "mono8",
00107                         clipped_mask).toImageMsg());
00108 
00109     cv::Mat clipped_image = image(region);
00110     cv::Mat masked_image;
00111     clipped_image.copyTo(masked_image, clipped_mask);
00112 
00113     cv::Mat output_image;
00114     if (mask_black_to_transparent_) {
00115       if (sensor_msgs::image_encodings::isMono(image_msg->encoding)) {
00116         cv::cvtColor(masked_image, output_image, CV_GRAY2BGRA);
00117       }
00118       else if (isRGB(image_msg->encoding)) {
00119         cv::cvtColor(masked_image, output_image, CV_RGB2BGRA);
00120       }
00121       else {  // BGR, BGRA or RGBA
00122         cv::cvtColor(masked_image, output_image, CV_BGR2BGRA);
00123       }
00124       for (size_t j=0; j<clipped_mask.rows; j++) {
00125         for (int i=0; i<clipped_mask.cols; i++) {
00126           if (clipped_mask.at<uchar>(j, i) == 0) {
00127             cv::Vec4b color = output_image.at<cv::Vec4b>(j, i);
00128             color[3] = 0;  // mask black -> transparent
00129             output_image.at<cv::Vec4b>(j, i) = color;
00130           }
00131         }
00132       }
00133       // publish bgr8 image
00134       pub_image_.publish(cv_bridge::CvImage(
00135             image_msg->header,
00136             sensor_msgs::image_encodings::BGRA8,
00137             output_image).toImageMsg());
00138     }
00139     else {
00140       if (isBGRA(image_msg->encoding)) {
00141         cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2BGRA);
00142       }
00143       else if (isRGBA(image_msg->encoding)) {
00144         cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2RGBA);
00145       }
00146       else {  // BGR, RGB or GRAY
00147         masked_image.copyTo(output_image);
00148       }
00149       pub_image_.publish(cv_bridge::CvImage(
00150             image_msg->header,
00151             image_msg->encoding,
00152             output_image).toImageMsg());
00153     }
00154   }
00155 }
00156 
00157 #include <pluginlib/class_list_macros.h>
00158 PLUGINLIB_EXPORT_CLASS (jsk_perception::ApplyMaskImage, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15