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_object_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 BoundingObjectMaskImage::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00049 onInitPostProcess();
00050 }
00051
00052 void BoundingObjectMaskImage::subscribe()
00053 {
00054 sub_ = pnh_->subscribe("input", 1, &BoundingObjectMaskImage::convert, this);
00055 ros::V_string names = boost::assign::list_of("~input");
00056 jsk_topic_tools::warnNoRemap(names);
00057 }
00058
00059 void BoundingObjectMaskImage::unsubscribe()
00060 {
00061 sub_.shutdown();
00062 }
00063
00064 void BoundingObjectMaskImage::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 cv::Mat object_mask = cv::Mat::zeros(mask_msg->height, mask_msg->width, CV_8UC1);
00077
00078 if (contours.size() != 0) {
00079
00080 boost::tuple<int, double> max_area;
00081 for (size_t i = 0; i < contours.size(); i++) {
00082 double area = cv::contourArea(contours[i]);
00083 if (area > max_area.get<1>()) {
00084 max_area = boost::make_tuple<int, double>(i, area);
00085 }
00086 }
00087 cv::drawContours(object_mask, contours, max_area.get<0>(), cv::Scalar(255), CV_FILLED);
00088 }
00089
00090 pub_.publish(cv_bridge::CvImage(
00091 mask_msg->header,
00092 sensor_msgs::image_encodings::MONO8,
00093 object_mask).toImageMsg());
00094 }
00095
00096 }
00097
00098 #include <pluginlib/class_list_macros.h>
00099 PLUGINLIB_EXPORT_CLASS(jsk_perception::BoundingObjectMaskImage, nodelet::Nodelet);