threshold_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016, 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/or 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 // https://github.com/opencv/opencv/blob/2.4/samples/cpp/tutorial_code/ImgProc/Threshold.cpp
00041 #include <image_transport/image_transport.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045 
00046 #include <opencv2/highgui/highgui.hpp>
00047 #include "opencv2/imgproc/imgproc.hpp"
00048 
00049 #include "opencv_apps/nodelet.h"
00050 #include "opencv_apps/ThresholdConfig.h"
00051 
00052 #include <dynamic_reconfigure/server.h>
00053 
00054 namespace threshold {
00055   class ThresholdNodelet : public opencv_apps::Nodelet {
00057     // Dynamic Reconfigure
00059     typedef threshold::ThresholdConfig Config;
00060     typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00061     Config config_;
00062     boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00063 
00064     bool debug_view_;
00065 
00066     std::string window_name_;
00067 
00068     image_transport::Publisher img_pub_;
00069     image_transport::Subscriber img_sub_;
00070     image_transport::CameraSubscriber cam_sub_;
00071 
00072     boost::shared_ptr<image_transport::ImageTransport> it_;
00073 
00074     boost::mutex mutex_;
00075     int threshold_type_;
00076     int max_binary_value_;
00077     int threshold_value_;
00078     bool apply_otsu_;
00079 
00080     void imageCallbackWithInfo(
00081       const sensor_msgs::ImageConstPtr& msg,
00082       const sensor_msgs::CameraInfoConstPtr& cam_info) {
00083       do_work(msg, cam_info->header.frame_id);
00084     }
00085 
00086     void imageCallback(const sensor_msgs::ImageConstPtr& msg) {
00087       do_work(msg, msg->header.frame_id);
00088     }
00089 
00090     void subscribe() {
00091       NODELET_DEBUG("Subscribing to image topic.");
00092       if (config_.use_camera_info)
00093         cam_sub_ = it_->subscribeCamera(
00094           "image", 1, &ThresholdNodelet::imageCallbackWithInfo, this);
00095       else
00096         img_sub_ =
00097           it_->subscribe("image", 1, &ThresholdNodelet::imageCallback, this);
00098     }
00099 
00100     void unsubscribe() {
00101       NODELET_DEBUG("Unsubscribing from image topic.");
00102       img_sub_.shutdown();
00103       cam_sub_.shutdown();
00104     }
00105 
00106     void reconfigureCallback(Config& config, uint32_t level) {
00107       boost::mutex::scoped_lock lock(mutex_);
00108       config_ = config;
00109       threshold_value_ = config.threshold;
00110       threshold_type_ = config.threshold_type;
00111       max_binary_value_ = config.max_binary;
00112       apply_otsu_ = config.apply_otsu;
00113     }
00114 
00115     void do_work(const sensor_msgs::Image::ConstPtr& image_msg,
00116                   const std::string input_frame_from_msg) {
00117       try {
00118         cv::Mat src_image =
00119           cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00120         cv::Mat gray_image;
00121         cv::cvtColor(src_image, gray_image, cv::COLOR_BGR2GRAY);
00122         cv::Mat result_image;
00123 
00124         if (apply_otsu_) {
00125           threshold_type_ |= CV_THRESH_OTSU;
00126         }
00127         cv::threshold(gray_image, result_image, threshold_value_,
00128                      max_binary_value_, threshold_type_);
00129         //-- Show what you got
00130         if (debug_view_) {
00131           cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00132           cv::imshow(window_name_, result_image);
00133           int c = cv::waitKey(1);
00134         }
00135         img_pub_.publish(cv_bridge::CvImage(image_msg->header,
00136                                             sensor_msgs::image_encodings::MONO8,
00137                                             result_image).toImageMsg());
00138       }
00139       catch (cv::Exception& e) {
00140         NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(),
00141                       e.func.c_str(), e.file.c_str(), e.line);
00142       }
00143     }
00144 
00145   public:
00146     virtual void onInit() {
00147       Nodelet::onInit();
00148       it_ = boost::shared_ptr<image_transport::ImageTransport>(
00149         new image_transport::ImageTransport(*nh_));
00150 
00151       pnh_->param("debug_view", debug_view_, false);
00152       if (debug_view_) {
00153         always_subscribe_ = true;
00154       }
00156       // Dynamic Reconfigure
00158       reconfigure_server_ =
00159         boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00160       dynamic_reconfigure::Server<Config>::CallbackType f =
00161         boost::bind(&ThresholdNodelet::reconfigureCallback, this, _1, _2);
00162       reconfigure_server_->setCallback(f);
00163 
00164       img_pub_ = advertiseImage(*pnh_, "image", 1);
00165       onInitPostProcess();
00166     }
00167   };
00168 }
00169 
00170 #include <pluginlib/class_list_macros.h>
00171 PLUGINLIB_EXPORT_CLASS(threshold::ThresholdNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:59