edge_detector.cpp
Go to the documentation of this file.
00001 #include <nodelet/nodelet.h>
00002 #include <jsk_perception/EdgeDetectorConfig.h>
00003 #include <image_transport/image_transport.h>
00004 #include <cv_bridge/cv_bridge.h>
00005 #include <sensor_msgs/image_encodings.h>
00006 #include <opencv2/imgproc/imgproc.hpp>
00007 #include "opencv2/highgui/highgui.hpp"
00008 
00009 #include <dynamic_reconfigure/server.h>
00010 
00011 #include <pluginlib/class_list_macros.h>
00012 
00013 namespace enc = sensor_msgs::image_encodings;
00014 
00015 namespace jsk_perception {
00016 class EdgeDetector: public nodelet::Nodelet
00017 {
00018     jsk_perception::EdgeDetectorConfig config_;
00019     dynamic_reconfigure::Server<jsk_perception::EdgeDetectorConfig> srv;
00020 
00021     image_transport::Publisher img_pub_;
00022     image_transport::Subscriber img_sub_;
00023 
00024     boost::shared_ptr<image_transport::ImageTransport> it_;
00025     ros::NodeHandle nh_;
00026     int subscriber_count_;
00027 
00028     double _threshold1;
00029     double _threshold2;
00030     int _apertureSize;
00031     bool _L2gradient;
00032 
00033     void reconfigureCallback(jsk_perception::EdgeDetectorConfig &new_config, uint32_t level)
00034     {
00035         config_ = new_config;
00036         _threshold1 = config_.threshold1;
00037         _threshold2 = config_.threshold2;
00038         _apertureSize = config_.apertureSize;
00039         _L2gradient = config_.L2gradient;
00040         if (subscriber_count_)
00041             { // @todo Could do this without an interruption at some point.
00042                 unsubscribe();
00043                 subscribe();
00044             }
00045     }
00046 
00047     void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00048     {
00049         do_work(msg, msg->header.frame_id);
00050     }
00051 
00052     void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00053     {
00054         // Transform the image.
00055         try
00056             {
00057                 // Convert the image into something opencv can handle.
00058                 cv::Mat in_image = cv_bridge::toCvShare(msg, msg->encoding)->image;
00059 
00060                 // Do the work
00061                 cv::Mat out_image;
00062                 if(in_image.channels() >= 3){
00063                   cv::cvtColor(in_image, out_image, CV_BGR2GRAY);
00064                 }else{
00065                   out_image = in_image;
00066                 }
00067                 cv::blur(out_image, out_image, cv::Size(_apertureSize,_apertureSize));
00068                 cv::Canny(out_image, out_image, _threshold1, _threshold2, _apertureSize, _L2gradient);
00069 
00070                 // Publish the image.
00071                 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, enc::MONO8, out_image).toImageMsg();
00072                 img_pub_.publish(out_img);
00073             }
00074         catch (cv::Exception &e)
00075             {
00076                 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00077             }
00078     }
00079 
00080     void subscribe()
00081     {
00082         NODELET_DEBUG("Subscribing to image topic.");
00083         img_sub_ = it_->subscribe("image", 3, &EdgeDetector::imageCallback, this);
00084     }
00085 
00086     void unsubscribe()
00087     {
00088         NODELET_DEBUG("Unsubscribing from image topic.");
00089         img_sub_.shutdown();
00090     }
00091 
00092     void connectCb(const image_transport::SingleSubscriberPublisher& ssp)
00093     {
00094         if (subscriber_count_++ == 0) {
00095             subscribe();
00096         }
00097     }
00098 
00099     void disconnectCb(const image_transport::SingleSubscriberPublisher&)
00100     {
00101         subscriber_count_--;
00102         if (subscriber_count_ == 0) {
00103             unsubscribe();
00104         }
00105     }
00106 
00107 public:
00108     void onInit() {
00109       nh_ = getNodeHandle();
00110       it_.reset(new image_transport::ImageTransport(nh_));
00111       subscriber_count_ = 0;
00112       image_transport::SubscriberStatusCallback connect_cb    = boost::bind(&EdgeDetector::connectCb, this, _1);
00113       image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&EdgeDetector::disconnectCb, this, _1);
00114       img_pub_ = image_transport::ImageTransport(ros::NodeHandle(nh_, "edge")).advertise("image", 1, connect_cb, disconnect_cb);
00115 
00116       dynamic_reconfigure::Server<jsk_perception::EdgeDetectorConfig>::CallbackType f =
00117         boost::bind(&EdgeDetector::reconfigureCallback, this, _1, _2);
00118       srv.setCallback(f);
00119     }
00120   
00121 };
00122 }
00123 
00124 typedef jsk_perception::EdgeDetector EdgeDetector;
00125 PLUGINLIB_DECLARE_CLASS (jsk_perception, EdgeDetector, EdgeDetector, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito
autogenerated on Mon Oct 6 2014 01:16:59