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


rqt_image_view
Author(s): Dirk Thomas
autogenerated on Fri Jan 3 2014 11:54:15