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/apply_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 ApplyMaskImage::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049 pnh_->param("approximate_sync", approximate_sync_, false);
00050 pnh_->param("clip", clip_, true);
00051 pnh_->param("negative", negative_, false);
00052 pnh_->param("negative/before_clip", negative_before_clip_, true);
00053 pnh_->param("mask_black_to_transparent", mask_black_to_transparent_, false);
00054 pnh_->param("queue_size", queue_size_, 100);
00055 pnh_->param("cval", cval_, 0);
00056 pub_image_ = advertise<sensor_msgs::Image>(
00057 *pnh_, "output", 1);
00058 pub_mask_ = advertise<sensor_msgs::Image>(
00059 *pnh_, "output/mask", 1);
00060 onInitPostProcess();
00061 }
00062
00063 void ApplyMaskImage::subscribe()
00064 {
00065 sub_image_.subscribe(*pnh_, "input", 1);
00066 sub_mask_.subscribe(*pnh_, "input/mask", 1);
00067 if (approximate_sync_) {
00068 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00069 async_->connectInput(sub_image_, sub_mask_);
00070 async_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
00071 }
00072 else {
00073 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00074 sync_->connectInput(sub_image_, sub_mask_);
00075 sync_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
00076 }
00077 ros::V_string names = boost::assign::list_of("~input")("~input/mask");
00078 jsk_topic_tools::warnNoRemap(names);
00079 }
00080
00081 void ApplyMaskImage::unsubscribe()
00082 {
00083 sub_image_.unsubscribe();
00084 sub_mask_.unsubscribe();
00085 }
00086
00087 void ApplyMaskImage::apply(
00088 const sensor_msgs::Image::ConstPtr& image_msg,
00089 const sensor_msgs::Image::ConstPtr& mask_msg)
00090 {
00091 vital_checker_->poke();
00092 cv::Mat image;
00093 if (jsk_recognition_utils::isBGRA(image_msg->encoding)) {
00094 cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00095 cv::cvtColor(tmp_image, image, cv::COLOR_BGRA2BGR);
00096 }
00097 else if (jsk_recognition_utils::isRGBA(image_msg->encoding)) {
00098 cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00099 cv::cvtColor(tmp_image, image, cv::COLOR_RGBA2BGR);
00100 }
00101 else {
00102 image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00103 }
00104 cv::Mat mask = cv_bridge::toCvShare(mask_msg, "mono8")->image;
00105 if (image.cols != mask.cols || image.rows != mask.rows) {
00106 NODELET_ERROR("size of image and mask is different");
00107 NODELET_ERROR("image: %dx%dx", image.cols, image.rows);
00108 NODELET_ERROR("mask: %dx%dx", mask.cols, mask.rows);
00109 return;
00110 }
00111
00112 if (negative_ && negative_before_clip_) {
00113 cv::bitwise_not(mask, mask);
00114 }
00115
00116 if (clip_) {
00117 cv::Rect region = jsk_recognition_utils::boundingRectOfMaskImage(mask);
00118 mask = mask(region);
00119 image = image(region);
00120 }
00121
00122 if (negative_ && !negative_before_clip_) {
00123 cv::bitwise_not(mask, mask);
00124 }
00125
00126 pub_mask_.publish(cv_bridge::CvImage(
00127 mask_msg->header,
00128 "mono8",
00129 mask).toImageMsg());
00130
00131 cv::Mat masked_image = image.clone();
00132 masked_image.setTo(cval_);
00133 image.copyTo(masked_image, mask);
00134
00135 cv::Mat output_image;
00136 if (mask_black_to_transparent_) {
00137 if (sensor_msgs::image_encodings::isMono(image_msg->encoding)) {
00138 cv::cvtColor(masked_image, output_image, CV_GRAY2BGRA);
00139 }
00140 else if (jsk_recognition_utils::isRGB(image_msg->encoding)) {
00141 cv::cvtColor(masked_image, output_image, CV_RGB2BGRA);
00142 }
00143 else {
00144 cv::cvtColor(masked_image, output_image, CV_BGR2BGRA);
00145 }
00146 for (size_t j=0; j < mask.rows; j++) {
00147 for (int i=0; i < mask.cols; i++) {
00148 if (mask.at<uchar>(j, i) == 0) {
00149 cv::Vec4b color = output_image.at<cv::Vec4b>(j, i);
00150 color[3] = 0;
00151 output_image.at<cv::Vec4b>(j, i) = color;
00152 }
00153 }
00154 }
00155
00156 pub_image_.publish(cv_bridge::CvImage(
00157 image_msg->header,
00158 sensor_msgs::image_encodings::BGRA8,
00159 output_image).toImageMsg());
00160 }
00161 else {
00162 if (jsk_recognition_utils::isBGRA(image_msg->encoding)) {
00163 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2BGRA);
00164 }
00165 else if (jsk_recognition_utils::isRGBA(image_msg->encoding)) {
00166 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2RGBA);
00167 }
00168 else {
00169 masked_image.copyTo(output_image);
00170 }
00171 pub_image_.publish(cv_bridge::CvImage(
00172 image_msg->header,
00173 image_msg->encoding,
00174 output_image).toImageMsg());
00175 }
00176 }
00177 }
00178
00179 #include <pluginlib/class_list_macros.h>
00180 PLUGINLIB_EXPORT_CLASS (jsk_perception::ApplyMaskImage, nodelet::Nodelet);