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/grabcut.h"
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <opencv2/opencv.hpp>
00040
00041 namespace jsk_perception
00042 {
00043 void GrabCut::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00047 dynamic_reconfigure::Server<Config>::CallbackType f =
00048 boost::bind (
00049 &GrabCut::configCallback, this, _1, _2);
00050 srv_->setCallback (f);
00051 pub_foreground_
00052 = advertise<sensor_msgs::Image>(*pnh_, "output/foreground", 1);
00053 pub_background_
00054 = advertise<sensor_msgs::Image>(*pnh_, "output/background", 1);
00055 pub_foreground_mask_
00056 = advertise<sensor_msgs::Image>(*pnh_, "output/foreground_mask", 1);
00057 pub_background_mask_
00058 = advertise<sensor_msgs::Image>(*pnh_, "output/background_mask", 1);
00059 }
00060
00061 void GrabCut::subscribe()
00062 {
00063 sub_image_.subscribe(*pnh_, "input", 1);
00064 sub_foreground_.subscribe(*pnh_, "input/foreground", 1);
00065 sub_background_.subscribe(*pnh_, "input/background", 1);
00066 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00067 sync_->connectInput(sub_image_, sub_foreground_, sub_background_);
00068 sync_->registerCallback(boost::bind(&GrabCut::segment,
00069 this, _1, _2, _3));
00070 }
00071
00072 void GrabCut::unsubscribe()
00073 {
00074 sub_image_.unsubscribe();
00075 sub_foreground_.unsubscribe();
00076 sub_background_.unsubscribe();
00077 }
00078
00079 void GrabCut::updateDiagnostic(
00080 diagnostic_updater::DiagnosticStatusWrapper &stat)
00081 {
00082
00083
00084 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00085 "GrabCut running");
00086 }
00087
00088 void GrabCut::segment(
00089 const sensor_msgs::Image::ConstPtr& image_msg,
00090 const sensor_msgs::Image::ConstPtr& foreground_msg,
00091 const sensor_msgs::Image::ConstPtr& background_msg)
00092 {
00093 boost::mutex::scoped_lock lock(mutex_);
00094 cv::Mat input;
00095 cv::Mat in_image = cv_bridge::toCvShare(image_msg,
00096 image_msg->encoding)->image;
00097 if (in_image.channels() == 3) {
00098 input = in_image;
00099 }
00100 else if (in_image.channels() == 1) {
00101 input = cv::Mat::zeros(in_image.rows, in_image.cols, CV_8UC3);
00102 for (size_t j = 0; j < in_image.rows; ++j) {
00103 for (size_t i = 0; i < in_image.cols; ++i) {
00104 input.at<cv::Vec3b>(j, i) = cv::Vec3b(in_image.at<uchar>(j, i),
00105 in_image.at<uchar>(j, i),
00106 in_image.at<uchar>(j, i));
00107 }
00108 }
00109 }
00110 cv::Mat foreground = cv_bridge::toCvCopy(
00111 foreground_msg, sensor_msgs::image_encodings::MONO8)->image;
00112 cv::Mat background = cv_bridge::toCvCopy(
00113 background_msg, sensor_msgs::image_encodings::MONO8)->image;
00114 if (!(input.cols == foreground.cols &&
00115 input.rows == foreground.rows &&
00116 background.cols == foreground.cols &&
00117 background.rows == foreground.rows)) {
00118 JSK_NODELET_WARN("size of image is not corretct");
00119 return;
00120 }
00121 cv::Mat mask = cv::Mat::zeros(input.size(), CV_8UC1);
00122 mask.setTo(cv::Scalar::all(cv::GC_PR_BGD));
00123 for (size_t j = 0; j < input.rows; j++) {
00124 for (size_t i = 0; i < input.cols; i++) {
00125 if (foreground.at<uchar>(j, i) == 255) {
00126 if (use_probable_pixel_seed_) {
00127 mask.at<uchar>(j, i) = cv::GC_PR_FGD;
00128 }
00129 else {
00130 mask.at<uchar>(j, i) = cv::GC_FGD;
00131 }
00132 }
00133 if (background.at<uchar>(j, i) == 255) {
00134 if (use_probable_pixel_seed_) {
00135 mask.at<uchar>(j, i) = cv::GC_PR_BGD;
00136 }
00137 else {
00138 mask.at<uchar>(j, i) = cv::GC_BGD;
00139 }
00140 }
00141 }
00142 }
00143 cv::Rect roi;
00144 cv::Mat bgd_model;
00145 cv::Mat fgd_model;
00146
00147 cv::grabCut(input, mask, roi, bgd_model, fgd_model, 5, cv::GC_INIT_WITH_MASK);
00148 cv::Mat bgd, fgd, bgd_mask, fgd_mask;
00149
00150
00151 bgd_mask = (mask == cv::GC_BGD) | (mask == cv::GC_PR_BGD);
00152
00153 fgd_mask = (mask == cv::GC_FGD) | (mask == cv::GC_PR_FGD);
00154
00155 input.copyTo(bgd, bgd_mask);
00156 input.copyTo(fgd, fgd_mask);
00157 cv_bridge::CvImage fg_bridge(
00158 image_msg->header, sensor_msgs::image_encodings::BGR8, fgd);
00159 cv_bridge::CvImage bg_bridge(
00160 image_msg->header, sensor_msgs::image_encodings::BGR8, bgd);
00161 cv_bridge::CvImage fg_mask_bridge(
00162 image_msg->header, sensor_msgs::image_encodings::MONO8, fgd_mask);
00163 cv_bridge::CvImage bg_mask_bridge(
00164 image_msg->header, sensor_msgs::image_encodings::MONO8, bgd_mask);
00165 pub_foreground_.publish(fg_bridge.toImageMsg());
00166 pub_background_.publish(bg_bridge.toImageMsg());
00167 pub_foreground_mask_.publish(fg_mask_bridge.toImageMsg());
00168 pub_background_mask_.publish(bg_mask_bridge.toImageMsg());
00169 }
00170
00171 void GrabCut::configCallback(Config &config, uint32_t level)
00172 {
00173 boost::mutex::scoped_lock lock(mutex_);
00174 use_probable_pixel_seed_ = (config.seed_pixel_policy == 1);
00175 }
00176
00177 }
00178
00179 #include <pluginlib/class_list_macros.h>
00180 PLUGINLIB_EXPORT_CLASS (jsk_perception::GrabCut, nodelet::Nodelet);