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 #include "jsk_perception/label_to_mask_image.h"
00036 #include <jsk_topic_tools/log_utils.h>
00037 #include <sensor_msgs/Image.h>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <boost/assign.hpp>
00041
00042 namespace jsk_perception
00043 {
00044
00045 void LabelToMaskImage::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048
00049 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050 dynamic_reconfigure::Server<Config>::CallbackType f =
00051 boost::bind(&LabelToMaskImage::configCallback, this, _1, _2);
00052 srv_->setCallback(f);
00053
00054 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00055 onInitPostProcess();
00056 }
00057
00058 void LabelToMaskImage::configCallback(
00059 Config &config, uint32_t level)
00060 {
00061 boost::mutex::scoped_lock lock(mutex_);
00062 label_value_ = config.label_value;
00063 }
00064
00065 void LabelToMaskImage::subscribe()
00066 {
00067 sub_ = pnh_->subscribe("input", 1,
00068 &LabelToMaskImage::convert,
00069 this);
00070 ros::V_string names = boost::assign::list_of("~input");
00071 jsk_topic_tools::warnNoRemap(names);
00072 }
00073
00074 void LabelToMaskImage::unsubscribe()
00075 {
00076 sub_.shutdown();
00077 }
00078
00079 void LabelToMaskImage::convert(
00080 const sensor_msgs::Image::ConstPtr& label_msg)
00081 {
00082 cv_bridge::CvImagePtr label_img_ptr = cv_bridge::toCvCopy(
00083 label_msg, sensor_msgs::image_encodings::TYPE_32SC1);
00084
00085 cv::Mat mask_image = cv::Mat::zeros(label_msg->height,
00086 label_msg->width,
00087 CV_8UC1);
00088 for (size_t j = 0; j < label_img_ptr->image.rows; j++)
00089 {
00090 for (size_t i = 0; i < label_img_ptr->image.cols; i++)
00091 {
00092 int label = label_img_ptr->image.at<int>(j, i);
00093 if (label == label_value_) {
00094 mask_image.at<uchar>(j, i) = 255;
00095 }
00096 }
00097 }
00098 pub_.publish(cv_bridge::CvImage(
00099 label_msg->header,
00100 sensor_msgs::image_encodings::MONO8,
00101 mask_image).toImageMsg());
00102 }
00103
00104 }
00105
00106 #include <pluginlib/class_list_macros.h>
00107 PLUGINLIB_EXPORT_CLASS(jsk_perception::LabelToMaskImage, nodelet::Nodelet);