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 <QMessageBox>
00043 #include <QPainter>
00044 
00045 namespace rqt_image_view {
00046 
00047 ImageView::ImageView()
00048   : rqt_gui_cpp::Plugin()
00049   , widget_(0)
00050 {
00051   setObjectName("ImageView");
00052 }
00053 
00054 void ImageView::initPlugin(qt_gui_cpp::PluginContext& context)
00055 {
00056   widget_ = new QWidget();
00057   ui_.setupUi(widget_);
00058 
00059   if (context.serialNumber() > 1)
00060   {
00061     widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
00062   }
00063   context.addWidget(widget_);
00064 
00065   updateTopicList();
00066   ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText(""));
00067   connect(ui_.topics_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(onTopicChanged(int)));
00068 
00069   ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh"));
00070   connect(ui_.refresh_topics_push_button, SIGNAL(pressed()), this, SLOT(updateTopicList()));
00071 
00072   ui_.zoom_1_push_button->setIcon(QIcon::fromTheme("zoom-original"));
00073   connect(ui_.zoom_1_push_button, SIGNAL(toggled(bool)), this, SLOT(onZoom1(bool)));
00074   
00075   connect(ui_.dynamic_range_check_box, SIGNAL(toggled(bool)), this, SLOT(onDynamicRange(bool)));
00076 }
00077 
00078 void ImageView::shutdownPlugin()
00079 {
00080   subscriber_.shutdown();
00081 }
00082 
00083 void ImageView::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
00084 {
00085   QString topic = ui_.topics_combo_box->currentText();
00086   //qDebug("ImageView::saveSettings() topic '%s'", topic.toStdString().c_str());
00087   instance_settings.setValue("topic", topic);
00088   instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked());
00089   instance_settings.setValue("dynamic_range", ui_.dynamic_range_check_box->isChecked());
00090   instance_settings.setValue("max_range", ui_.max_range_double_spin_box->value());
00091 }
00092 
00093 void ImageView::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
00094 {
00095   bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
00096   ui_.zoom_1_push_button->setChecked(zoom1_checked);
00097 
00098   bool dynamic_range_checked = instance_settings.value("dynamic_range", false).toBool();
00099   ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
00100 
00101   double max_range = instance_settings.value("max_range", ui_.max_range_double_spin_box->value()).toDouble();
00102   ui_.max_range_double_spin_box->setValue(max_range);
00103 
00104   QString topic = instance_settings.value("topic", "").toString();
00105   //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str());
00106   selectTopic(topic);
00107 }
00108 
00109 void ImageView::updateTopicList()
00110 {
00111   QSet<QString> message_types;
00112   message_types.insert("sensor_msgs/Image");
00113   QSet<QString> message_sub_types;
00114   message_sub_types.insert("sensor_msgs/CompressedImage");
00115 
00116   // get declared transports
00117   QList<QString> transports;
00118   image_transport::ImageTransport it(getNodeHandle());
00119   std::vector<std::string> declared = it.getDeclaredTransports();
00120   for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
00121   {
00122     //qDebug("ImageView::updateTopicList() declared transport '%s'", it->c_str());
00123     QString transport = it->c_str();
00124 
00125     // strip prefix from transport name
00126     QString prefix = "image_transport/";
00127     if (transport.startsWith(prefix))
00128     {
00129       transport = transport.mid(prefix.length());
00130     }
00131     transports.append(transport);
00132   }
00133 
00134   QString selected = ui_.topics_combo_box->currentText();
00135 
00136   // fill combo box
00137   QList<QString> topics = getTopics(message_types, message_sub_types, transports).values();
00138   topics.append("");
00139   qSort(topics);
00140   ui_.topics_combo_box->clear();
00141   for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
00142   {
00143     QString label(*it);
00144     label.replace(" ", "/");
00145     ui_.topics_combo_box->addItem(label, QVariant(*it));
00146   }
00147 
00148   // restore previous selection
00149   selectTopic(selected);
00150 }
00151 
00152 QList<QString> ImageView::getTopicList(const QSet<QString>& message_types, const QList<QString>& transports)
00153 {
00154   QSet<QString> message_sub_types;
00155   return getTopics(message_types, message_sub_types, transports).values();
00156 }
00157 
00158 QSet<QString> ImageView::getTopics(const QSet<QString>& message_types, const QSet<QString>& message_sub_types, const QList<QString>& transports)
00159 {
00160   ros::master::V_TopicInfo topic_info;
00161   ros::master::getTopics(topic_info);
00162 
00163   QSet<QString> all_topics;
00164   for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00165   {
00166     all_topics.insert(it->name.c_str());
00167   }
00168 
00169   QSet<QString> topics;
00170   for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
00171   {
00172     if (message_types.contains(it->datatype.c_str()))
00173     {
00174       QString topic = it->name.c_str();
00175 
00176       // add raw topic
00177       topics.insert(topic);
00178       //qDebug("ImageView::getTopics() raw topic '%s'", topic.toStdString().c_str());
00179 
00180       // add transport specific sub-topics
00181       for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
00182       {
00183         if (all_topics.contains(topic + "/" + *jt))
00184         {
00185           QString sub = topic + " " + *jt;
00186           topics.insert(sub);
00187           //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", sub.toStdString().c_str());
00188         }
00189       }
00190     }
00191     if (message_sub_types.contains(it->datatype.c_str()))
00192     {
00193       QString topic = it->name.c_str();
00194       int index = topic.lastIndexOf("/");
00195       if (index != -1)
00196       {
00197         topic.replace(index, 1, " ");
00198         topics.insert(topic);
00199         //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", topic.toStdString().c_str());
00200       }
00201     }
00202   }
00203   return topics;
00204 }
00205 
00206 void ImageView::selectTopic(const QString& topic)
00207 {
00208   int index = ui_.topics_combo_box->findText(topic);
00209   if (index == -1)
00210   {
00211     index = ui_.topics_combo_box->findText("");
00212   }
00213   ui_.topics_combo_box->setCurrentIndex(index);
00214 }
00215 
00216 void ImageView::onTopicChanged(int index)
00217 {
00218   subscriber_.shutdown();
00219 
00220   // reset image on topic change
00221   ui_.image_frame->setImage(QImage());
00222 
00223   QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" ");
00224   QString topic = parts.first();
00225   QString transport = parts.length() == 2 ? parts.last() : "raw";
00226 
00227   if (!topic.isEmpty())
00228   {
00229     image_transport::ImageTransport it(getNodeHandle());
00230     image_transport::TransportHints hints(transport.toStdString());
00231     try {
00232       subscriber_ = it.subscribe(topic.toStdString(), 1, &ImageView::callbackImage, this, hints);
00233       //qDebug("ImageView::onTopicChanged() to topic '%s' with transport '%s'", topic.toStdString().c_str(), subscriber_.getTransport().c_str());
00234     } catch (image_transport::TransportLoadException& e) {
00235       QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what());
00236     }
00237   }
00238 }
00239 
00240 void ImageView::onZoom1(bool checked)
00241 {
00242   if (checked)
00243   {
00244     if (ui_.image_frame->getImage().isNull())
00245     {
00246       return;
00247     }
00248     ui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size());
00249     widget_->resize(ui_.image_frame->size());
00250     widget_->setMinimumSize(widget_->sizeHint());
00251     widget_->setMaximumSize(widget_->sizeHint());
00252   } else {
00253     ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
00254     ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00255     widget_->setMinimumSize(QSize(80, 60));
00256     widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
00257   }
00258 }
00259 
00260 void ImageView::onDynamicRange(bool checked)
00261 {
00262   ui_.max_range_double_spin_box->setEnabled(!checked);
00263 }
00264 
00265 void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
00266 {
00267   try
00268   {
00269     // First let cv_bridge do its magic
00270     cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
00271     conversion_mat_ = cv_ptr->image;
00272   }
00273   catch (cv_bridge::Exception& e)
00274   {
00275     try
00276     {
00277       // If we're here, there is no conversion that makes sense, but let's try to imagine a few first
00278       cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg);
00279       if (msg->encoding == "CV_8UC3")
00280       {
00281         // assuming it is rgb
00282         conversion_mat_ = cv_ptr->image;
00283       } else if (msg->encoding == "8UC1") {
00284         // convert gray to rgb
00285         cv::cvtColor(cv_ptr->image, conversion_mat_, CV_GRAY2RGB);
00286       } else if (msg->encoding == "16UC1" || msg->encoding == "32FC1") {
00287         // scale / quantify
00288         double min = 0;
00289         double max = ui_.max_range_double_spin_box->value();
00290         if (msg->encoding == "16UC1") max *= 1000;
00291         if (ui_.dynamic_range_check_box->isChecked())
00292         {
00293           // dynamically adjust range based on min/max in image
00294           cv::minMaxLoc(cv_ptr->image, &min, &max);
00295           if (min == max) {
00296             // completely homogeneous images are displayed in gray
00297             min = 0;
00298             max = 2;
00299           }
00300         }
00301         cv::Mat img_scaled_8u;
00302         cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
00303         cv::cvtColor(img_scaled_8u, conversion_mat_, CV_GRAY2RGB);
00304       } else {
00305         qWarning("ImageView.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
00306         ui_.image_frame->setImage(QImage());
00307         return;
00308       }
00309     }
00310     catch (cv_bridge::Exception& e)
00311     {
00312       qWarning("ImageView.callback_image() while trying to convert image from '%s' to 'rgb8' an exception was thrown (%s)", msg->encoding.c_str(), e.what());
00313       ui_.image_frame->setImage(QImage());
00314       return;
00315     }
00316   }
00317 
00318   // image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
00319   QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, conversion_mat_.step[0], QImage::Format_RGB888);
00320   ui_.image_frame->setImage(image);
00321 
00322   if (!ui_.zoom_1_push_button->isEnabled())
00323   {
00324     ui_.zoom_1_push_button->setEnabled(true);
00325     onZoom1(ui_.zoom_1_push_button->isChecked());
00326   }
00327 }
00328 
00329 }
00330 
00331 PLUGINLIB_EXPORT_CLASS(rqt_image_view::ImageView, rqt_gui_cpp::Plugin)


rqt_image_view
Author(s): Dirk Thomas
autogenerated on Mon Oct 6 2014 07:15:02