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/bounding_rect_mask_image.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_recognition_utils/cv_utils.h>
00039 #include <opencv2/opencv.hpp>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042
00043 namespace jsk_perception
00044 {
00045 void BoundingRectMaskImage::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00049 onInitPostProcess();
00050 }
00051
00052 void BoundingRectMaskImage::subscribe()
00053 {
00054 sub_ = pnh_->subscribe("input", 1, &BoundingRectMaskImage::convert, this);
00055 ros::V_string names = boost::assign::list_of("~input");
00056 jsk_topic_tools::warnNoRemap(names);
00057 }
00058
00059 void BoundingRectMaskImage::unsubscribe()
00060 {
00061 sub_.shutdown();
00062 }
00063
00064 void BoundingRectMaskImage::convert(
00065 const sensor_msgs::Image::ConstPtr& mask_msg)
00066 {
00067 vital_checker_->poke();
00068 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00069 mask_msg, sensor_msgs::image_encodings::MONO8);
00070 cv::Mat mask = cv_ptr->image;
00071
00072
00073 std::vector<std::vector<cv::Point> > contours;
00074 cv::findContours(mask, contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
00075
00076 if (contours.size() == 0) {
00077 NODELET_ERROR_THROTTLE(30, "[%s] Skipping because no contour is found", __PRETTY_FUNCTION__);
00078 return;
00079 }
00080
00081
00082 boost::tuple<int, double> max_area;
00083 for (size_t i = 0; i < contours.size(); i++) {
00084 double area = cv::contourArea(contours[i]);
00085 if (area > max_area.get<1>()) {
00086 max_area = boost::make_tuple<int, double>(i, area);
00087 }
00088 }
00089
00090
00091 std::vector<cv::Point> max_area_contour = contours[max_area.get<0>()];
00092 cv::Rect rect = cv::boundingRect(cv::Mat(max_area_contour));
00093
00094
00095 cv::Mat rect_mask = cv::Mat::zeros(mask_msg->height, mask_msg->width, CV_8UC1);
00096 cv::rectangle(rect_mask, rect, cv::Scalar(255), CV_FILLED);
00097
00098 pub_.publish(cv_bridge::CvImage(
00099 mask_msg->header,
00100 sensor_msgs::image_encodings::MONO8,
00101 rect_mask).toImageMsg());
00102 }
00103
00104 }
00105
00106 #include <pluginlib/class_list_macros.h>
00107 PLUGINLIB_EXPORT_CLASS(jsk_perception::BoundingRectMaskImage, nodelet::Nodelet);