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/contour_finder.h"
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <opencv2/opencv.hpp>
00040
00041
00042 namespace jsk_perception
00043 {
00044 void ContourFinder::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pub_debug_image_ = advertise<sensor_msgs::Image>(*pnh_, "debug", 1);
00048 pub_convex_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/convex", 1);
00049 }
00050
00051 void ContourFinder::subscribe()
00052 {
00053 sub_ = pnh_->subscribe("input", 1, &ContourFinder::segment, this);
00054 }
00055
00056 void ContourFinder::unsubscribe()
00057 {
00058 sub_.shutdown();
00059 }
00060
00061 void ContourFinder::segment(
00062 const sensor_msgs::Image::ConstPtr& image_msg)
00063 {
00064 std::vector<std::vector<cv::Point> > contours;
00065 std::vector<std::vector<cv::Point> > convex_contours(1);
00066 std::vector<cv::Vec4i> hierarchy;
00067 cv::RNG rng(12345);
00068 cv::Mat input = cv_bridge::toCvCopy(
00069 image_msg, sensor_msgs::image_encodings::MONO8)->image;
00070 cv::findContours(input, contours, hierarchy, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00071 cv::Mat drawing = cv::Mat::zeros(input.size(), CV_8UC3);
00072 for( int i = 0; i< contours.size(); i++ )
00073 {
00074 cv::Scalar color = cv::Scalar( rng.uniform(0, 255), rng.uniform(0,255), rng.uniform(0,255) );
00075 cv::drawContours(drawing, contours, i, color, CV_FILLED, 8, hierarchy, 0, cv::Point());
00076 }
00077 pub_debug_image_.publish(cv_bridge::CvImage(
00078 image_msg->header,
00079 sensor_msgs::image_encodings::BGR8,
00080 drawing).toImageMsg());
00081
00082 std::vector<cv::Point> all_contours;
00083 for (size_t i = 0; i < contours.size(); i++) {
00084 for (size_t j = 0; j < contours[i].size(); j++) {
00085 all_contours.push_back(contours[i][j]);
00086 }
00087 }
00088
00089 cv::convexHull(cv::Mat(all_contours), convex_contours[0]);
00090 cv::Mat convex_image = cv::Mat::zeros(input.size(), CV_8UC1);
00091 cv::drawContours(convex_image, convex_contours, 0, cv::Scalar(255), CV_FILLED);
00092 pub_convex_image_.publish(
00093 cv_bridge::CvImage(
00094 image_msg->header,
00095 sensor_msgs::image_encodings::MONO8,
00096 convex_image).toImageMsg());
00097 }
00098 }
00099
00100 #include <pluginlib/class_list_macros.h>
00101 PLUGINLIB_EXPORT_CLASS (jsk_perception::ContourFinder, nodelet::Nodelet);
00102