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_to_rect.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040
00041 namespace jsk_perception
00042 {
00043 void MaskImageToRect::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_ = advertise<geometry_msgs::PolygonStamped>(*pnh_, "output", 1);
00047 }
00048
00049 void MaskImageToRect::subscribe()
00050 {
00051 sub_mask_ = pnh_->subscribe("input", 1, &MaskImageToRect::convert, this);
00052 }
00053
00054 void MaskImageToRect::unsubscribe()
00055 {
00056 sub_mask_.shutdown();
00057 }
00058
00059 void MaskImageToRect::convert(
00060 const sensor_msgs::Image::ConstPtr& mask_msg)
00061 {
00062 vital_checker_->poke();
00063 std::vector<cv::Point> indices;
00064 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00065 mask_msg, sensor_msgs::image_encodings::MONO8);
00066 cv::Mat mask = cv_ptr->image;
00067 for (size_t j = 0; j < mask.rows; j++) {
00068 for (size_t i = 0; i < mask.cols; i++) {
00069 if (mask.at<uchar>(j, i) == 255) {
00070 indices.push_back(cv::Point(i, j));
00071 }
00072 }
00073 }
00074 cv::Rect mask_rect = cv::boundingRect(indices);
00075 geometry_msgs::PolygonStamped rect;
00076 rect.header = mask_msg->header;
00077 geometry_msgs::Point32 min_pt, max_pt;
00078 min_pt.x = mask_rect.x;
00079 min_pt.y = mask_rect.y;
00080 max_pt.x = mask_rect.x + mask_rect.width;
00081 max_pt.y = mask_rect.y + mask_rect.height;
00082 rect.polygon.points.push_back(min_pt);
00083 rect.polygon.points.push_back(max_pt);
00084 pub_.publish(rect);
00085 }
00086
00087 }
00088
00089 #include <pluginlib/class_list_macros.h>
00090 PLUGINLIB_EXPORT_CLASS (jsk_perception::MaskImageToRect, nodelet::Nodelet);