image_view.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Dirk Thomas, TU Darmstadt
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions
00007  * are met:
00008  *
00009  *   * Redistributions of source code must retain the above copyright
00010  *     notice, this list of conditions and the following disclaimer.
00011  *   * Redistributions in binary form must reproduce the above
00012  *     copyright notice, this list of conditions and the following
00013  *     disclaimer in the documentation and/or other materials provided
00014  *     with the distribution.
00015  *   * Neither the name of the TU Darmstadt nor the names of its
00016  *     contributors may be used to endorse or promote products derived
00017  *     from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00022  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00023  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00024  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00025  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00028  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00029  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00030  * POSSIBILITY OF SUCH DAMAGE.
00031  */
00032 
00033 #include <rqt_image_view/image_view.h>
00034 
00035 #include <pluginlib/class_list_macros.h>
00036 #include <ros/master.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <opencv2/imgproc/imgproc.hpp>
00041 
00042 #include <QFileDialog>
00043 #include <QMessageBox>
00044 #include <QPainter>
00045 
00046 namespace rqt_image_view {
00047 
00048 ImageView::ImageView()
00049   : rqt_gui_cpp::Plugin()
00050   , widget_(0)
00051 {
00052   setObjectName("ImageView");
00053 }
00054 
00055 void ImageView::initPlugin(qt_gui_cpp::PluginContext& context)
00056 {
00057   widget_ = new QWidget();
00058   ui_.setupUi(widget_);
00059 
00060   if (context.serialNumber() > 1)
00061   {
00062     widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
00063   }
00064   context.addWidget(widget_);
00065 
00066   updateTopicList();
00067   ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText(""));
00068   connect(ui_.topics_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(onTopicChanged(int)));
00069 
00070   ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh"));
00071   connect(ui_.refresh_topics_push_button, SIGNAL(pressed()), this, SLOT(updateTopicList()));
00072 
00073   ui_.zoom_1_push_button->setIcon(QIcon::fromTheme("zoom-original"));
00074   connect(ui_.zoom_1_push_button, SIGNAL(toggled(bool)), this, SLOT(onZoom1(bool)));
00075 
00076   connect(ui_.dynamic_range_check_box, SIGNAL(toggled(bool)), this, SLOT(onDynamicRange(bool)));
00077 
00078   ui_.save_as_image_push_button->setIcon(QIcon::fromTheme("image"));
00079   connect(ui_.save_as_image_push_button, SIGNAL(pressed()), this, SLOT(saveImage()));
00080 
00081   // set topic name if passed in as argument
00082   const QStringList& argv = context.argv();
00083   if (!argv.empty()) {
00084     arg_topic_name = argv[0];
00085     // add topic name to list if not yet in
00086     int index = ui_.topics_combo_box->findText(arg_topic_name);
00087     if (index == -1) {
00088       QString label(arg_topic_name);
00089       label.replace(" ", "/");
00090       ui_.topics_combo_box->addItem(label, QVariant(arg_topic_name));
00091       ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText(arg_topic_name));
00092     }
00093   }
00094 }
00095 
00096 void ImageView::shutdownPlugin()
00097 {
00098   subscriber_.shutdown();
00099 }
00100 
00101 void ImageView::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
00102 {
00103   QString topic = ui_.topics_combo_box->currentText();
00104   //qDebug("ImageView::saveSettings() topic '%s'", topic.toStdString().c_str());
00105   instance_settings.setValue("topic", topic);
00106   instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked());
00107   instance_settings.setValue("dynamic_range", ui_.dynamic_range_check_box->isChecked());
00108   instance_settings.setValue("max_range", ui_.max_range_double_spin_box->value());
00109 }
00110 
00111 void ImageView::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
00112 {
00113   bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
00114   ui_.zoom_1_push_button->setChecked(zoom1_checked);
00115 
00116   bool dynamic_range_checked = instance_settings.value("dynamic_range", false).toBool();
00117   ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
00118 
00119   double max_range = instance_settings.value("max_range", ui_.max_range_double_spin_box->value()).toDouble();
00120   ui_.max_range_double_spin_box->setValue(max_range);
00121 
00122   QString topic = instance_settings.value("topic", "").toString();
00123   // don't overwrite topic name passed as command line argument
00124   if (!arg_topic_name.isEmpty())
00125   {
00126     arg_topic_name = "";
00127   }
00128   else
00129   {
00130     //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str());
00131     selectTopic(topic);
00132   }
00133 }
00134 
00135 void ImageView::updateTopicList()
00136 {
00137   QSet<QString> message_types;
00138   message_types.insert("sensor_msgs/Image");
00139   QSet<QString> message_sub_types;
00140   message_sub_types.insert("sensor_msgs/CompressedImage");
00141 
00142   // get declared transports
00143   QList<QString> transports;
00144   image_transport::ImageTransport it(getNodeHandle());
00145   std::vector<std::string> declared = it.getDeclaredTransports();
00146   for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
00147   {
00148     //qDebug("ImageView::updateTopicList() declared transport '%s'", it->c_str());
00149     QString transport = it->c_str();
00150 
00151     // strip prefix from transport name
00152     QString prefix = "image_transport/";
00153     if (transport.startsWith(prefix))
00154     {
00155       transport = transport.mid(prefix.length());
00156     }
00157     transports.append(transport);
00158   }
00159 
00160   QString selected = ui_.topics_combo_box->currentText();
00161 
00162   // fill combo box
00163   QList<QString> topics = getTopics(message_types, message_sub_types, transports).values();
00164   topics.append("");
00165   qSort(topics);
00166   ui_.topics_combo_box->clear();
00167   for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
00168   {
00169     QString label(*it);
00170     label.replace(" ", "/");
00171     ui_.topics_combo_box->addItem(label, QVariant(*it));
00172   }
00173 
00174   // restore previous selection
00175   selectTopic(selected);
00176 }
00177 
00178 QList<QString> ImageView::getTopicList(const QSet<QString>& message_types, const QList<QString>& transports)
00179 {
00180   QSet<QString> message_sub_types;
00181   return getTopics(message_types, message_sub_types, transports).values();
00182 }
00183 
00184 QSet<QString> ImageView::getTopics(const QSet<QString>& message_types, const QSet<QString>& message_sub_types, const QList<QString>& transports)
00185 {
00186   ros::master::V_TopicInfo topic_info;
00187   ros::master::getTopics(topic_info);
00188 
00189   QSet<QString> all_topics;
00190   for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00191   {
00192     all_topics.insert(it->name.c_str());
00193   }
00194 
00195   QSet<QString> topics;
00196   for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00197   {
00198     if (message_types.contains(it->datatype.c_str()))
00199     {
00200       QString topic = it->name.c_str();
00201 
00202       // add raw topic
00203       topics.insert(topic);
00204       //qDebug("ImageView::getTopics() raw topic '%s'", topic.toStdString().c_str());
00205 
00206       // add transport specific sub-topics
00207       for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
00208       {
00209         if (all_topics.contains(topic + "/" + *jt))
00210         {
00211           QString sub = topic + " " + *jt;
00212           topics.insert(sub);
00213           //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", sub.toStdString().c_str());
00214         }
00215       }
00216     }
00217     if (message_sub_types.contains(it->datatype.c_str()))
00218     {
00219       QString topic = it->name.c_str();
00220       int index = topic.lastIndexOf("/");
00221       if (index != -1)
00222       {
00223         topic.replace(index, 1, " ");
00224         topics.insert(topic);
00225         //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", topic.toStdString().c_str());
00226       }
00227     }
00228   }
00229   return topics;
00230 }
00231 
00232 void ImageView::selectTopic(const QString& topic)
00233 {
00234   int index = ui_.topics_combo_box->findText(topic);
00235   if (index == -1)
00236   {
00237     index = ui_.topics_combo_box->findText("");
00238   }
00239   ui_.topics_combo_box->setCurrentIndex(index);
00240 }
00241 
00242 void ImageView::onTopicChanged(int index)
00243 {
00244   subscriber_.shutdown();
00245 
00246   // reset image on topic change
00247   ui_.image_frame->setImage(QImage());
00248 
00249   QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" ");
00250   QString topic = parts.first();
00251   QString transport = parts.length() == 2 ? parts.last() : "raw";
00252 
00253   if (!topic.isEmpty())
00254   {
00255     image_transport::ImageTransport it(getNodeHandle());
00256     image_transport::TransportHints hints(transport.toStdString());
00257     try {
00258       subscriber_ = it.subscribe(topic.toStdString(), 1, &ImageView::callbackImage, this, hints);
00259       //qDebug("ImageView::onTopicChanged() to topic '%s' with transport '%s'", topic.toStdString().c_str(), subscriber_.getTransport().c_str());
00260     } catch (image_transport::TransportLoadException& e) {
00261       QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what());
00262     }
00263   }
00264 }
00265 
00266 void ImageView::onZoom1(bool checked)
00267 {
00268   if (checked)
00269   {
00270     if (ui_.image_frame->getImage().isNull())
00271     {
00272       return;
00273     }
00274     ui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size());
00275     widget_->resize(ui_.image_frame->size());
00276     widget_->setMinimumSize(widget_->sizeHint());
00277     widget_->setMaximumSize(widget_->sizeHint());
00278   } else {
00279     ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
00280     ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00281     widget_->setMinimumSize(QSize(80, 60));
00282     widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00283   }
00284 }
00285 
00286 void ImageView::onDynamicRange(bool checked)
00287 {
00288   ui_.max_range_double_spin_box->setEnabled(!checked);
00289 }
00290 
00291 void ImageView::saveImage()
00292 {
00293   // take a snapshot before asking for the filename
00294   QImage img = ui_.image_frame->getImageCopy();
00295 
00296   QString file_name = QFileDialog::getSaveFileName(widget_, tr("Save as image"), "image.png", tr("Image (*.bmp *.jpg *.png *.tiff)"));
00297   if (file_name.isEmpty())
00298   {
00299     return;
00300   }
00301 
00302   img.save(file_name);
00303 }
00304 
00305 void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
00306 {
00307   try
00308   {
00309     // First let cv_bridge do its magic
00310     cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
00311     conversion_mat_ = cv_ptr->image;
00312   }
00313   catch (cv_bridge::Exception& e)
00314   {
00315     try
00316     {
00317       // If we're here, there is no conversion that makes sense, but let's try to imagine a few first
00318       cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg);
00319       if (msg->encoding == "CV_8UC3")
00320       {
00321         // assuming it is rgb
00322         conversion_mat_ = cv_ptr->image;
00323       } else if (msg->encoding == "8UC1") {
00324         // convert gray to rgb
00325         cv::cvtColor(cv_ptr->image, conversion_mat_, CV_GRAY2RGB);
00326       } else if (msg->encoding == "16UC1" || msg->encoding == "32FC1") {
00327         // scale / quantify
00328         double min = 0;
00329         double max = ui_.max_range_double_spin_box->value();
00330         if (msg->encoding == "16UC1") max *= 1000;
00331         if (ui_.dynamic_range_check_box->isChecked())
00332         {
00333           // dynamically adjust range based on min/max in image
00334           cv::minMaxLoc(cv_ptr->image, &min, &max);
00335           if (min == max) {
00336             // completely homogeneous images are displayed in gray
00337             min = 0;
00338             max = 2;
00339           }
00340         }
00341         cv::Mat img_scaled_8u;
00342         cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
00343         cv::cvtColor(img_scaled_8u, conversion_mat_, CV_GRAY2RGB);
00344       } else {
00345         qWarning("ImageView.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
00346         ui_.image_frame->setImage(QImage());
00347         return;
00348       }
00349     }
00350     catch (cv_bridge::Exception& e)
00351     {
00352       qWarning("ImageView.callback_image() while trying to convert image from '%s' to 'rgb8' an exception was thrown (%s)", msg->encoding.c_str(), e.what());
00353       ui_.image_frame->setImage(QImage());
00354       return;
00355     }
00356   }
00357 
00358   // image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
00359   QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, conversion_mat_.step[0], QImage::Format_RGB888);
00360   ui_.image_frame->setImage(image);
00361 
00362   if (!ui_.zoom_1_push_button->isEnabled())
00363   {
00364     ui_.zoom_1_push_button->setEnabled(true);
00365     onZoom1(ui_.zoom_1_push_button->isChecked());
00366   }
00367 }
00368 
00369 }
00370 
00371 PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin)


rqt_image_view
Author(s): Dirk Thomas
autogenerated on Wed Sep 16 2015 06:57:52