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 <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 UnapplyMaskImage::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pnh_->param("approximate_sync", approximate_sync_, false);
00048 pub_image_ = advertise<sensor_msgs::Image>(
00049 *pnh_, "output", 1);
00050 }
00051
00052 void UnapplyMaskImage::subscribe()
00053 {
00054 sub_image_.subscribe(*pnh_, "input", 1);
00055 sub_mask_.subscribe(*pnh_, "input/mask", 1);
00056 if (approximate_sync_) {
00057 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
00058 async_->connectInput(sub_image_, sub_mask_);
00059 async_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, _1, _2));
00060 }
00061 else {
00062 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00063 sync_->connectInput(sub_image_, sub_mask_);
00064 sync_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, _1, _2));
00065 }
00066 }
00067
00068 void UnapplyMaskImage::unsubscribe()
00069 {
00070 sub_image_.unsubscribe();
00071 sub_mask_.unsubscribe();
00072 }
00073
00074 void UnapplyMaskImage::apply(
00075 const sensor_msgs::Image::ConstPtr& image_msg,
00076 const sensor_msgs::Image::ConstPtr& mask_msg)
00077 {
00078 vital_checker_->poke();
00079 cv::Mat image = cv_bridge::toCvShare(image_msg,
00080 image_msg->encoding)->image;
00081 cv::Mat mask = cv_bridge::toCvShare(mask_msg,
00082 mask_msg->encoding)->image;
00083 cv::Mat output;
00084 bool single_channel = false;
00085 if (image_msg->encoding == sensor_msgs::image_encodings::BGR8 ||
00086 image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00087 single_channel = false;
00088 }
00089 else {
00090 single_channel = true;
00091 }
00092 if (single_channel) {
00093 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC1);
00094 }
00095 else {
00096 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC3);
00097 }
00098
00099 cv::Rect region = boundingRectOfMaskImage(mask);
00100 for (int j = 0; j < image.rows; j++) {
00101 for (int i = 0; i < image.cols; i++) {
00102 if (single_channel) {
00103 output.at<uchar>(j + region.y, i + region.x)
00104 = image.at<uchar>(j, i);
00105 }
00106 else {
00107 output.at<cv::Vec3b>(j + region.y, i + region.x)
00108 = image.at<cv::Vec3b>(j, i);
00109 }
00110 }
00111 }
00112 pub_image_.publish(cv_bridge::CvImage(
00113 image_msg->header,
00114 image_msg->encoding,
00115 output).toImageMsg());
00116 }
00117 }
00118
00119 #include <pluginlib/class_list_macros.h>
00120 PLUGINLIB_EXPORT_CLASS (jsk_perception::UnapplyMaskImage, nodelet::Nodelet);