Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_perception/unapply_mask_image.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <opencv2/opencv.hpp>
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <jsk_recognition_utils/cv_utils.h>
00043
00044 namespace jsk_perception
00045 {
00046 void UnapplyMaskImage::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049 pnh_->param("approximate_sync", approximate_sync_, false);
00050 pub_image_ = advertise<sensor_msgs::Image>(
00051 *pnh_, "output", 1);
00052 onInitPostProcess();
00053 }
00054
00055 void UnapplyMaskImage::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(&UnapplyMaskImage::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(&UnapplyMaskImage::apply, this, _1, _2));
00068 }
00069 ros::V_string names = boost::assign::list_of("~input")("~input/mask");
00070 jsk_topic_tools::warnNoRemap(names);
00071 }
00072
00073 void UnapplyMaskImage::unsubscribe()
00074 {
00075 sub_image_.unsubscribe();
00076 sub_mask_.unsubscribe();
00077 }
00078
00079 void UnapplyMaskImage::apply(
00080 const sensor_msgs::Image::ConstPtr& image_msg,
00081 const sensor_msgs::Image::ConstPtr& mask_msg)
00082 {
00083 vital_checker_->poke();
00084 cv::Mat image = cv_bridge::toCvShare(image_msg,
00085 image_msg->encoding)->image;
00086 cv::Mat mask = cv_bridge::toCvShare(mask_msg,
00087 mask_msg->encoding)->image;
00088 cv::Mat output;
00089 bool single_channel = false;
00090 if (image_msg->encoding == sensor_msgs::image_encodings::BGR8 ||
00091 image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00092 single_channel = false;
00093 }
00094 else {
00095 single_channel = true;
00096 }
00097 if (single_channel) {
00098 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC1);
00099 }
00100 else {
00101 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC3);
00102 }
00103
00104 cv::Rect region = jsk_recognition_utils::boundingRectOfMaskImage(mask);
00105 for (int j = 0; j < image.rows; j++) {
00106 for (int i = 0; i < image.cols; i++) {
00107 if (single_channel) {
00108 output.at<uchar>(j + region.y, i + region.x)
00109 = image.at<uchar>(j, i);
00110 }
00111 else {
00112 output.at<cv::Vec3b>(j + region.y, i + region.x)
00113 = image.at<cv::Vec3b>(j, i);
00114 }
00115 }
00116 }
00117 pub_image_.publish(cv_bridge::CvImage(
00118 image_msg->header,
00119 image_msg->encoding,
00120 output).toImageMsg());
00121 }
00122 }
00123
00124 #include <pluginlib/class_list_macros.h>
00125 PLUGINLIB_EXPORT_CLASS (jsk_perception::UnapplyMaskImage, nodelet::Nodelet);