image_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #include <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <opencv2/highgui/highgui.hpp>
00040 #include "window_thread.h"
00041 
00042 #include <boost/thread.hpp>
00043 #include <boost/format.hpp>
00044 
00045 #ifdef HAVE_GTK
00046 #include <gtk/gtk.h>
00047 
00048 // Platform-specific workaround for #3026: image_view doesn't close when
00049 // closing image window. On platforms using GTK+ we connect this to the
00050 // window's "destroy" event so that image_view exits.
00051 static void destroyNode(GtkWidget *widget, gpointer data)
00052 {
00054   //ros::shutdown();
00055   exit(0); // brute force solution
00056 }
00057 
00058 static void destroyNodelet(GtkWidget *widget, gpointer data)
00059 {
00060   // We can't actually unload the nodelet from here, but we can at least
00061   // unsubscribe from the image topic.
00062   reinterpret_cast<image_transport::Subscriber*>(data)->shutdown();
00063 }
00064 #endif
00065 
00066 
00067 namespace image_view {
00068 
00069 class ImageNodelet : public nodelet::Nodelet
00070 {
00071   image_transport::Subscriber sub_;
00072 
00073   boost::mutex image_mutex_;
00074   cv::Mat last_image_;
00075   
00076   std::string window_name_;
00077   boost::format filename_format_;
00078   int count_;
00079 
00080   virtual void onInit();
00081   
00082   void imageCb(const sensor_msgs::ImageConstPtr& msg);
00083 
00084   static void mouseCb(int event, int x, int y, int flags, void* param);
00085 
00086 public:
00087   ImageNodelet();
00088 
00089   ~ImageNodelet();
00090 };
00091 
00092 ImageNodelet::ImageNodelet()
00093   : filename_format_(""), count_(0)
00094 {
00095 }
00096 
00097 ImageNodelet::~ImageNodelet()
00098 {
00099   cv::destroyWindow(window_name_);
00100 }
00101 
00102 void ImageNodelet::onInit()
00103 {
00104   ros::NodeHandle nh = getNodeHandle();
00105   ros::NodeHandle local_nh = getPrivateNodeHandle();
00106 
00107   // Command line argument parsing
00108   const std::vector<std::string>& argv = getMyArgv();
00109   // First positional argument is the transport type
00110   std::string transport;
00111   local_nh.param("image_transport", transport, std::string("raw"));
00112   for (int i = 0; i < (int)argv.size(); ++i)
00113   {
00114     if (argv[i][0] != '-')
00115     {
00116       transport = argv[i];
00117       break;
00118     }
00119   }
00120   NODELET_INFO_STREAM("Using transport \"" << transport << "\"");
00121   // Internal option, should be used only by the image_view node
00122   bool shutdown_on_close = std::find(argv.begin(), argv.end(),
00123                                      "--shutdown-on-close") != argv.end();
00124 
00125   // Default window name is the resolved topic name
00126   std::string topic = nh.resolveName("image");
00127   local_nh.param("window_name", window_name_, topic);
00128 
00129   bool autosize;
00130   local_nh.param("autosize", autosize, false);
00131   
00132   std::string format_string;
00133   local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
00134   filename_format_.parse(format_string);
00135 
00136   cv::namedWindow(window_name_, autosize ? cv::WND_PROP_AUTOSIZE : 0);
00137   cv::setMouseCallback(window_name_, &ImageNodelet::mouseCb, this);
00138   
00139 #ifdef HAVE_GTK
00140   // Register appropriate handler for when user closes the display window
00141   GtkWidget *widget = GTK_WIDGET( cvGetWindowHandle(window_name_.c_str()) );
00142   if (shutdown_on_close)
00143     g_signal_connect(widget, "destroy", G_CALLBACK(destroyNode), NULL);
00144   else
00145     g_signal_connect(widget, "destroy", G_CALLBACK(destroyNodelet), &sub_);
00146 #endif
00147 
00148   // Start the OpenCV window thread so we don't have to waitKey() somewhere
00149   startWindowThread();
00150 
00151   image_transport::ImageTransport it(nh);
00152   image_transport::TransportHints hints(transport, ros::TransportHints(), getPrivateNodeHandle());
00153   sub_ = it.subscribe(topic, 1, &ImageNodelet::imageCb, this, hints);
00154 }
00155 
00156 void ImageNodelet::imageCb(const sensor_msgs::ImageConstPtr& msg)
00157 {
00158   image_mutex_.lock();
00159 
00160   // We want to scale floating point images so that they display nicely
00161   bool do_dynamic_scaling = (msg->encoding.find("F") != std::string::npos);
00162 
00163   // Convert to OpenCV native BGR color
00164   try {
00165     cv_bridge::CvtColorForDisplayOptions options;
00166     options.do_dynamic_scaling = do_dynamic_scaling;
00167     last_image_ = cvtColorForDisplay(cv_bridge::toCvShare(msg), "", options)->image;
00168   }
00169   catch (cv_bridge::Exception& e) {
00170     NODELET_ERROR_THROTTLE(30, "Unable to convert '%s' image for display: '%s'",
00171                              msg->encoding.c_str(), e.what());
00172   }
00173 
00174   // Must release the mutex before calling cv::imshow, or can deadlock against
00175   // OpenCV's window mutex.
00176   image_mutex_.unlock();
00177   if (!last_image_.empty())
00178     cv::imshow(window_name_, last_image_);
00179 }
00180 
00181 void ImageNodelet::mouseCb(int event, int x, int y, int flags, void* param)
00182 {
00183   ImageNodelet *this_ = reinterpret_cast<ImageNodelet*>(param);
00184   // Trick to use NODELET_* logging macros in static function
00185   boost::function<const std::string&()> getName =
00186     boost::bind(&ImageNodelet::getName, this_);
00187 
00188   if (event == cv::EVENT_LBUTTONDOWN)
00189   {
00190     NODELET_WARN_ONCE("Left-clicking no longer saves images. Right-click instead.");
00191     return;
00192   }
00193   if (event != cv::EVENT_RBUTTONDOWN)
00194     return;
00195   
00196   boost::lock_guard<boost::mutex> guard(this_->image_mutex_);
00197 
00198   const cv::Mat &image = this_->last_image_;
00199   if (image.empty())
00200   {
00201     NODELET_WARN("Couldn't save image, no data!");
00202     return;
00203   }
00204 
00205   std::string filename = (this_->filename_format_ % this_->count_).str();
00206   if (cv::imwrite(filename, image))
00207   {
00208     NODELET_INFO("Saved image %s", filename.c_str());
00209     this_->count_++;
00210   }
00211   else
00212   {
00214     NODELET_ERROR("Failed to save image.");
00215   }
00216 }
00217 
00218 } // namespace image_view
00219 
00220 // Register the nodelet
00221 #include <pluginlib/class_list_macros.h>
00222 PLUGINLIB_EXPORT_CLASS( image_view::ImageNodelet, nodelet::Nodelet)


image_view
Author(s): Patrick Mihelich
autogenerated on Tue Sep 19 2017 02:56:22