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/rect_to_mask_image.h"
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <sensor_msgs/image_encodings.h>
00039
00040 namespace jsk_perception
00041 {
00042 void RectToMaskImage::onInit()
00043 {
00044 DiagnosticNodelet::onInit();
00045 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00046 }
00047
00048 void RectToMaskImage::subscribe()
00049 {
00050 sub_ = pnh_->subscribe("input", 1, &RectToMaskImage::convert, this);
00051 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00052 &RectToMaskImage::infoCallback, this);
00053 }
00054
00055 void RectToMaskImage::unsubscribe()
00056 {
00057 sub_.shutdown();
00058 sub_info_.shutdown();
00059 }
00060
00061 void RectToMaskImage::convert(
00062 const geometry_msgs::PolygonStamped::ConstPtr& rect_msg)
00063 {
00064 boost::mutex::scoped_lock lock(mutex_);
00065 if (camera_info_) {
00066 cv::Mat mask_image = cv::Mat::zeros(camera_info_->height,
00067 camera_info_->width,
00068 CV_8UC1);
00069 geometry_msgs::Point32 P0 = rect_msg->polygon.points[0];
00070 geometry_msgs::Point32 P1 = rect_msg->polygon.points[1];
00071 double min_x = std::max(std::min(P0.x, P1.x), 0.0f);
00072 double max_x = std::max(P0.x, P1.x);
00073 double min_y = std::max(std::min(P0.y, P1.y), 0.0f);
00074 double max_y = std::max(P0.y, P1.y);
00075 double width = std::min(max_x - min_x, camera_info_->width - min_x);
00076 double height = std::min(max_y - min_y, camera_info_->height - min_y);
00077 cv::Rect region(min_x, min_y, width, height);
00078 cv::rectangle(mask_image, region, cv::Scalar(255), CV_FILLED);
00079 pub_.publish(cv_bridge::CvImage(
00080 rect_msg->header,
00081 sensor_msgs::image_encodings::MONO8,
00082 mask_image).toImageMsg());
00083 }
00084 }
00085
00086
00087 void RectToMaskImage::infoCallback(
00088 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00089 {
00090 boost::mutex::scoped_lock lock(mutex_);
00091 camera_info_ = info_msg;
00092 }
00093 }
00094
00095 #include <pluginlib/class_list_macros.h>
00096 PLUGINLIB_EXPORT_CLASS (jsk_perception::RectToMaskImage, nodelet::Nodelet);