image_nodelet.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 
00005 #include <cv_bridge/cv_bridge.h>
00006 #include <opencv2/highgui/highgui.hpp>
00007 #include "window_thread.h"
00008 
00009 #include <boost/thread.hpp>
00010 #include <boost/format.hpp>
00011 
00012 #ifdef HAVE_GTK
00013 #include <gtk/gtk.h>
00014 
00015 // Platform-specific workaround for #3026: image_view doesn't close when
00016 // closing image window. On platforms using GTK+ we connect this to the
00017 // window's "destroy" event so that image_view exits.
00018 static void destroyNode(GtkWidget *widget, gpointer data)
00019 {
00021   //ros::shutdown();
00022   exit(0); // brute force solution
00023 }
00024 
00025 static void destroyNodelet(GtkWidget *widget, gpointer data)
00026 {
00027   // We can't actually unload the nodelet from here, but we can at least
00028   // unsubscribe from the image topic.
00029   reinterpret_cast<image_transport::Subscriber*>(data)->shutdown();
00030 }
00031 #endif
00032 
00033 
00034 namespace image_view {
00035 
00036 class ImageNodelet : public nodelet::Nodelet
00037 {
00038   image_transport::Subscriber sub_;
00039 
00040   boost::mutex image_mutex_;
00041   sensor_msgs::ImageConstPtr last_msg_;
00042   cv::Mat last_image_;
00043   
00044   std::string window_name_;
00045   boost::format filename_format_;
00046   int count_;
00047 
00048   virtual void onInit();
00049   
00050   void imageCb(const sensor_msgs::ImageConstPtr& msg);
00051 
00052   static void mouseCb(int event, int x, int y, int flags, void* param);
00053 
00054 public:
00055   ImageNodelet();
00056 
00057   ~ImageNodelet();
00058 };
00059 
00060 ImageNodelet::ImageNodelet()
00061   : filename_format_(""), count_(0)
00062 {
00063 }
00064 
00065 ImageNodelet::~ImageNodelet()
00066 {
00067   cv::destroyWindow(window_name_);
00068 }
00069 
00070 void ImageNodelet::onInit()
00071 {
00072   ros::NodeHandle nh = getNodeHandle();
00073   ros::NodeHandle local_nh = getPrivateNodeHandle();
00074 
00075   // Command line argument parsing
00076   const std::vector<std::string>& argv = getMyArgv();
00077   // First positional argument is the transport type
00078   std::string transport = "raw";
00079   for (int i = 0; i < (int)argv.size(); ++i)
00080   {
00081     if (argv[i][0] != '-')
00082     {
00083       transport = argv[i];
00084       break;
00085     }
00086   }
00087   // Internal option, should be used only by the image_view node
00088   bool shutdown_on_close = std::find(argv.begin(), argv.end(),
00089                                      "--shutdown-on-close") != argv.end();
00090 
00091   // Default window name is the resolved topic name
00092   std::string topic = nh.resolveName("image");
00093   local_nh.param("window_name", window_name_, topic);
00094 
00095   bool autosize;
00096   local_nh.param("autosize", autosize, false);
00097   
00098   std::string format_string;
00099   local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
00100   filename_format_.parse(format_string);
00101 
00102   cv::namedWindow(window_name_, autosize ? CV_WINDOW_AUTOSIZE : 0);
00103   cv::setMouseCallback(window_name_, &ImageNodelet::mouseCb, this);
00104   
00105 #ifdef HAVE_GTK
00106   // Register appropriate handler for when user closes the display window
00107   GtkWidget *widget = GTK_WIDGET( cvGetWindowHandle(window_name_.c_str()) );
00108   if (shutdown_on_close)
00109     g_signal_connect(widget, "destroy", G_CALLBACK(destroyNode), NULL);
00110   else
00111     g_signal_connect(widget, "destroy", G_CALLBACK(destroyNodelet), &sub_);
00112 #endif
00113 
00114   // Start the OpenCV window thread so we don't have to waitKey() somewhere
00115   startWindowThread();
00116 
00117   image_transport::ImageTransport it(nh);
00118   image_transport::TransportHints hints(transport, ros::TransportHints(), getPrivateNodeHandle());
00119   sub_ = it.subscribe(topic, 1, &ImageNodelet::imageCb, this, hints);
00120 }
00121 
00122 void ImageNodelet::imageCb(const sensor_msgs::ImageConstPtr& msg)
00123 {
00124   image_mutex_.lock();
00125 
00126   // May want to view raw bayer data, which CvBridge doesn't know about
00127   if (msg->encoding.find("bayer") != std::string::npos)
00128   {
00129     last_image_ = cv::Mat(msg->height, msg->width, CV_8UC1,
00130                           const_cast<uint8_t*>(&msg->data[0]), msg->step);
00131   }
00132   // We want to scale floating point images so that they display nicely
00133   else if(msg->encoding.find("F") != std::string::npos)
00134   {
00135     cv::Mat float_image_bridge = cv_bridge::toCvShare(msg, msg->encoding)->image;
00136     cv::Mat_<float> float_image = float_image_bridge;
00137     float max_val = 0;
00138     for(int i = 0; i < float_image.rows; ++i)
00139     {
00140       for(int j = 0; j < float_image.cols; ++j)
00141       {
00142         max_val = std::max(max_val, float_image(i, j));
00143       }
00144     }
00145 
00146     if(max_val > 0)
00147     {
00148       float_image /= max_val;
00149     }
00150     last_image_ = float_image;
00151   }
00152   else
00153   {
00154     // Convert to OpenCV native BGR color
00155     try {
00156       last_image_ = cv_bridge::toCvShare(msg, "bgr8")->image;
00157     }
00158     catch (cv_bridge::Exception& e) {
00159       NODELET_ERROR_THROTTLE(30, "Unable to convert '%s' image to bgr8: '%s'",
00160                              msg->encoding.c_str(), e.what());
00161     }
00162   }
00163 
00164   // last_image_ may point to data owned by last_msg_, so we hang onto it for
00165   // the sake of mouseCb.
00166   last_msg_ = msg;
00167 
00168   // Must release the mutex before calling cv::imshow, or can deadlock against
00169   // OpenCV's window mutex.
00170   image_mutex_.unlock();
00171   if (!last_image_.empty())
00172     cv::imshow(window_name_, last_image_);
00173 }
00174 
00175 void ImageNodelet::mouseCb(int event, int x, int y, int flags, void* param)
00176 {
00177   ImageNodelet *this_ = reinterpret_cast<ImageNodelet*>(param);
00178   // Trick to use NODELET_* logging macros in static function
00179   boost::function<const std::string&()> getName =
00180     boost::bind(&ImageNodelet::getName, this_);
00181   
00182   if (event == CV_EVENT_LBUTTONDOWN)
00183   {
00184     NODELET_WARN_ONCE("Left-clicking no longer saves images. Right-click instead.");
00185     return;
00186   }
00187   if (event != CV_EVENT_RBUTTONDOWN)
00188     return;
00189   
00190   boost::lock_guard<boost::mutex> guard(this_->image_mutex_);
00191 
00192   const cv::Mat image = this_->last_image_;
00193   if (image.empty())
00194   {
00195     NODELET_WARN("Couldn't save image, no data!");
00196     return;
00197   }
00198 
00199   std::string filename = (this_->filename_format_ % this_->count_).str();
00200   if (cv::imwrite(filename, image))
00201   {
00202     NODELET_INFO("Saved image %s", filename.c_str());
00203     this_->count_++;
00204   }
00205   else
00206   {
00208     NODELET_ERROR("Failed to save image.");
00209   }
00210 }
00211 
00212 } // namespace image_view
00213 
00214 // Register the nodelet
00215 #include <pluginlib/class_list_macros.h>
00216 PLUGINLIB_DECLARE_CLASS(image_view, image, image_view::ImageNodelet, nodelet::Nodelet)


image_view
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:41