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