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