draw_rects.cpp
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2017, 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  * draw_rects.cpp
00037  * Author: furushchev <furushchev@jsk.imi.i.u-tokyo.ac.jp>
00038  */
00039 
00040 #include <jsk_perception/draw_rects.h>
00041 
00042 namespace enc = sensor_msgs::image_encodings;
00043 
00044 namespace jsk_perception
00045 {
00046 
00047   void DrawRects::onInit()
00048   {
00049     ConnectionBasedNodelet::onInit();
00050 
00051     srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00052     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00053       boost::bind(&DrawRects::configCallback, this, _1, _2);
00054     srv_->setCallback(f);
00055 
00056     pub_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00057 
00058     onInitPostProcess();
00059   }
00060 
00061   void DrawRects::subscribe()
00062   {
00063     sub_image_.subscribe(*pnh_, "input", 1);
00064     sub_rects_.subscribe(*pnh_, "input/rects", 1);
00065 
00066     if (use_classification_result_)
00067       sub_class_.subscribe(*pnh_, "input/class", 1);
00068     else
00069       sub_rects_.registerCallback(boost::bind(&DrawRects::fillEmptyClasses, this, _1));
00070 
00071     if (use_async_)
00072     {
00073       async_ = boost::make_shared<message_filters::Synchronizer<AsyncPolicy> >(queue_size_);
00074       if (use_classification_result_)
00075         async_->connectInput(sub_image_, sub_rects_, sub_class_);
00076       else
00077         async_->connectInput(sub_image_, sub_rects_, null_class_);
00078       async_->registerCallback(boost::bind(&DrawRects::onMessage, this, _1, _2, _3));
00079     } else {
00080       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00081       if (use_classification_result_)
00082         sync_->connectInput(sub_image_, sub_rects_, sub_class_);
00083       else
00084         sync_->connectInput(sub_image_, sub_rects_, null_class_);
00085       sync_->registerCallback(boost::bind(&DrawRects::onMessage, this, _1, _2, _3));
00086     }
00087   }
00088 
00089   void DrawRects::unsubscribe()
00090   {
00091     sub_image_.unsubscribe();
00092     sub_rects_.unsubscribe();
00093     if (use_classification_result_)
00094       sub_class_.unsubscribe();
00095   }
00096 
00097   void DrawRects::configCallback(Config& config, uint32_t level)
00098   {
00099     boost::mutex::scoped_lock lock(mutex_);
00100 
00101     bool need_resubscribe = false;
00102     if (use_async_ != config.approximate_sync ||
00103         queue_size_ != config.queue_size ||
00104         use_classification_result_ != config.use_classification_result)
00105       need_resubscribe = true;
00106 
00107     use_async_ = config.approximate_sync;
00108     queue_size_ = config.queue_size;
00109 
00110     use_classification_result_ = config.use_classification_result;
00111     show_proba_ = config.show_proba;
00112 
00113     rect_boldness_ = config.rect_boldness;
00114 
00115     label_size_ = config.label_size;
00116     label_boldness_ = config.label_boldness;
00117     label_font_ = config.label_font;
00118     label_margin_factor_ = config.label_margin_factor;
00119 
00120     resolution_factor_ = config.resolution_factor;
00121     interpolation_method_ = config.interpolation_method;
00122 #if ROS_VERSION_MINIMUM(1, 11, 4)
00123     // indigo or later
00124     if (need_resubscribe && isSubscribed()) {
00125       unsubscribe();
00126       subscribe();
00127     }
00128 #endif
00129   }
00130 
00131   void DrawRects::fillEmptyClasses(
00132       const jsk_recognition_msgs::RectArray::ConstPtr& rects)
00133   {
00134     jsk_recognition_msgs::ClassificationResult classes;
00135     classes.header = rects->header;
00136     null_class_.add(
00137       boost::make_shared<jsk_recognition_msgs::ClassificationResult>(classes));
00138   }
00139 
00140   void DrawRects::onMessage(
00141       const sensor_msgs::Image::ConstPtr& image,
00142       const jsk_recognition_msgs::RectArray::ConstPtr& rects,
00143       const jsk_recognition_msgs::ClassificationResult::ConstPtr& classes)
00144   {
00145     boost::mutex::scoped_lock lock(mutex_);
00146 
00147     cv_bridge::CvImage::Ptr cv_img;
00148     try {
00149       cv_img = cv_bridge::toCvCopy(image, enc::BGR8);
00150     } catch (cv_bridge::Exception &e) {
00151       NODELET_ERROR_STREAM("Failed to convert image: " << e.what());
00152       return;
00153     }
00154 
00155     cv::Mat img;
00156     cv::resize(cv_img->image, img, cv::Size(),
00157                resolution_factor_, resolution_factor_,
00158                interpolation_method_);
00159 
00160     int label_num = \
00161       use_classification_result_ ? classes->target_names.size() : rects->rects.size();
00162 
00163     for (size_t i = 0; i < rects->rects.size(); ++i) {
00164       int label_idx = use_classification_result_ ? classes->labels[i] : i;
00165       cv::Scalar color;
00166       randomColor(label_num, label_idx, color);
00167       drawRect(img, rects->rects[i], color);
00168 
00169       if (use_classification_result_)
00170       {
00171         std::ostringstream oss;
00172         oss << classes->label_names[i];
00173         if (show_proba_ && classes->label_proba.size() > i) {
00174           oss << std::fixed << std::setprecision(2);
00175           oss << " (" << classes->label_proba[i] << ")";
00176         }
00177         drawLabel(img, rects->rects[i], color, oss.str());
00178       }
00179     }
00180 
00181     pub_image_.publish(*cv_bridge::CvImage(image->header, enc::BGR8, img).toImageMsg());
00182   }
00183 
00184   void DrawRects::drawRect(
00185     cv::Mat& img, const jsk_recognition_msgs::Rect& orig_rect, const cv::Scalar& color)
00186   {
00187     cv::Rect rect(orig_rect.x * resolution_factor_,
00188                     orig_rect.y * resolution_factor_,
00189                     orig_rect.width * resolution_factor_,
00190                     orig_rect.height * resolution_factor_);
00191     cv::rectangle(img, rect, color, rect_boldness_, CV_AA);
00192   }
00193 
00194   void DrawRects::drawLabel(
00195     cv::Mat& img, const jsk_recognition_msgs::Rect& rect,
00196     const cv::Scalar& color, const std::string& label)
00197   {
00198     int baseline;
00199     cv::Size label_size = cv::getTextSize(label, label_font_,
00200                                           label_size_, label_boldness_,
00201                                           &baseline);
00202     int text_color = isDarkColor(color) ? 255 : 0;
00203 
00204     double orig_x = rect.x * resolution_factor_;
00205     double orig_y = rect.y * resolution_factor_;
00206 
00207     cv::rectangle(img,
00208                   cv::Rect(orig_x,
00209                            orig_y - label_size.height * label_margin_factor_ * 1.15,
00210                            label_size.width * label_margin_factor_,
00211                            label_size.height * label_margin_factor_ * 1.3),
00212                   color, -1, CV_AA);
00213     cv::putText(img, label,
00214                 cv::Point(orig_x + label_size.width  * (label_margin_factor_ - 1.0) / 2.0,
00215                           orig_y - label_size.height * (label_margin_factor_ - 1.0) / 2.0),
00216                 label_font_,
00217                 label_size_,
00218                 cv::Scalar(text_color, text_color, text_color),
00219                 label_boldness_,
00220                 CV_AA);
00221   }
00222 
00223   void DrawRects::randomColor(const int& label_num, const int& index, cv::Scalar& color)
00224   {
00225     static const float colors[6][3] = { {1,0,1}, {0,0,1},{0,1,1},{0,1,0},{1,1,0},{1,0,0} };
00226     float ratio = ((float)(index * 123457 % label_num) / label_num) * 5;
00227     int i = std::floor(ratio);
00228     int j = std::ceil(ratio);
00229     ratio -= i;
00230     for (int c = 0; c < 3; ++c)
00231       color[c] = (int)(((1-ratio) * colors[i][c] + ratio * colors[j][c]) * 255);
00232   }
00233 }
00234 
00235 #include <pluginlib/class_list_macros.h>
00236 PLUGINLIB_EXPORT_CLASS(jsk_perception::DrawRects, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07