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