polygon_array_to_label_image.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_perception/polygon_array_to_label_image.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 
00041 namespace jsk_perception
00042 {
00043   void PolygonArrayToLabelImage::onInit()
00044   {
00045     DiagnosticNodelet::onInit();
00046     pub_ = advertise<sensor_msgs::Image>(
00047       *pnh_, "output", 1);
00048   }
00049 
00050   void PolygonArrayToLabelImage::subscribe()
00051   {
00052     sub_info_ = pnh_->subscribe("input/camera_info", 1,
00053                                 &PolygonArrayToLabelImage::infoCallback, this);
00054     sub_ = pnh_->subscribe("input", 1,
00055                            &PolygonArrayToLabelImage::convert, this);
00056   }
00057 
00058   void PolygonArrayToLabelImage::unsubscribe()
00059   {
00060     sub_info_.shutdown();
00061     sub_.shutdown();
00062   }
00063 
00064   void PolygonArrayToLabelImage::infoCallback(
00065     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00066   {
00067     boost::mutex::scoped_lock lock(mutex_);
00068     camera_info_ = info_msg;
00069   }
00070 
00071   void PolygonArrayToLabelImage::convert(
00072     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
00073   {
00074     boost::mutex::scoped_lock lock(mutex_);
00075     vital_checker_->poke();
00076     if (camera_info_) {
00077       image_geometry::PinholeCameraModel model;
00078       model.fromCameraInfo(camera_info_);
00079       cv::Mat mask_image = cv::Mat::zeros(camera_info_->height,
00080                                           camera_info_->width,
00081                                           CV_32SC1);
00082       
00083       int label_counter = 1;
00084       // we expect same tf frame
00085       for (size_t i_polygon = 0; i_polygon < polygon_msg->polygons.size(); ++i_polygon) {
00086         geometry_msgs::Polygon polygon = polygon_msg->polygons[i_polygon].polygon;
00087         std::vector<cv::Point> points;
00088         if (polygon.points.size() >= 3) {
00089           bool all_outside = true;
00090           for (size_t i = 0; i < polygon.points.size(); i++) {
00091             geometry_msgs::Point32 p = polygon.points[i];
00092             cv::Point uv = model.project3dToPixel(cv::Point3d(p.x, p.y, p.z));
00093             if ((uv.x > 0 && uv.x < camera_info_->width) &&
00094                 (uv.y > 0 && uv.y < camera_info_->height)) {
00095               all_outside = false;
00096             }
00097             points.push_back(uv);
00098           }
00099           if (!all_outside) {
00100             cv::fillConvexPoly(mask_image, &(points[0]), points.size(), label_counter++);
00101           }
00102         }
00103       }
00104       pub_.publish(cv_bridge::CvImage(polygon_msg->header,
00105                                       sensor_msgs::image_encodings::TYPE_32SC1,
00106                                       mask_image).toImageMsg());
00107     }
00108     else {
00109       JSK_NODELET_WARN("no camera info is available");
00110     }
00111   }
00112 
00113 }
00114 
00115 #include <pluginlib/class_list_macros.h>
00116 PLUGINLIB_EXPORT_CLASS (jsk_perception::PolygonArrayToLabelImage, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15