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


hector_rqt_plugins
Author(s): Dirk Thomas, Thorsten Graber, Gregor Gebhardt
autogenerated on Mon Aug 15 2016 03:58:04