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/mask_image_generator.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <opencv2/opencv.hpp>
00042
00043
00044 namespace jsk_perception
00045 {
00046 void MaskImageGenerator::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050 dynamic_reconfigure::Server<Config>::CallbackType f =
00051 boost::bind (&MaskImageGenerator::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053
00054 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00055 onInitPostProcess();
00056 }
00057
00058 void MaskImageGenerator::subscribe()
00059 {
00060 sub_ = pnh_->subscribe("input", 1, &MaskImageGenerator::generate, this);
00061 ros::V_string names = boost::assign::list_of("~input");
00062 jsk_topic_tools::warnNoRemap(names);
00063 }
00064
00065 void MaskImageGenerator::unsubscribe()
00066 {
00067 sub_.shutdown();
00068 }
00069
00070 void MaskImageGenerator::configCallback(Config &config, uint32_t level)
00071 {
00072 boost::mutex::scoped_lock lock(mutex_);
00073 offset_x_ = config.offset_x;
00074 offset_y_ = config.offset_y;
00075 width_ = config.width;
00076 height_ = config.height;
00077 }
00078
00079 void MaskImageGenerator::generate(const sensor_msgs::Image::ConstPtr& msg)
00080 {
00081 boost::mutex::scoped_lock lock(mutex_);
00082 int min_x = std::min(offset_x_, (int)msg->width);
00083 int min_y = std::min(offset_y_, (int)msg->height);
00084 int max_x = std::min(min_x + width_, (int)msg->width);
00085 int max_y = std::min(min_y + height_, (int)msg->height);
00086 cv::Mat mask_image = cv::Mat::zeros(msg->height, msg->width, CV_8UC1);
00087 cv::rectangle(mask_image,
00088 cv::Point(min_x, min_y),
00089 cv::Point(max_x, max_y),
00090 cv::Scalar(255), CV_FILLED);
00091 pub_.publish(cv_bridge::CvImage(msg->header,
00092 sensor_msgs::image_encodings::MONO8,
00093 mask_image).toImageMsg());
00094 }
00095 }
00096
00097 #include <pluginlib/class_list_macros.h>
00098 PLUGINLIB_EXPORT_CLASS (jsk_perception::MaskImageGenerator, nodelet::Nodelet);