image_view.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Dirk Thomas, TU Darmstadt
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  * * Neither the name of the TU Darmstadt nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
34 
36 #include <ros/master.h>
38 
39 #include <cv_bridge/cv_bridge.h>
40 #include <opencv2/imgproc/imgproc.hpp>
41 
42 #include <QFileDialog>
43 #include <QMessageBox>
44 #include <QPainter>
45 
46 namespace rqt_image_view {
47 
49  : rqt_gui_cpp::Plugin()
50  , widget_(0)
51  , num_gridlines_(0)
52  , rotate_state_(ROTATE_0)
53 {
54  setObjectName("ImageView");
55 }
56 
58 {
59  widget_ = new QWidget();
60  ui_.setupUi(widget_);
61 
62  if (context.serialNumber() > 1)
63  {
64  widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
65  }
66  context.addWidget(widget_);
67 
69  ui_.color_scheme_combo_box->setCurrentIndex(ui_.color_scheme_combo_box->findText("Gray"));
70 
72  ui_.topics_combo_box->setCurrentIndex(ui_.topics_combo_box->findText(""));
73  connect(ui_.topics_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(onTopicChanged(int)));
74 
75  ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh"));
76  connect(ui_.refresh_topics_push_button, SIGNAL(pressed()), this, SLOT(updateTopicList()));
77 
78  ui_.zoom_1_push_button->setIcon(QIcon::fromTheme("zoom-original"));
79  connect(ui_.zoom_1_push_button, SIGNAL(toggled(bool)), this, SLOT(onZoom1(bool)));
80 
81  connect(ui_.dynamic_range_check_box, SIGNAL(toggled(bool)), this, SLOT(onDynamicRange(bool)));
82 
83  ui_.save_as_image_push_button->setIcon(QIcon::fromTheme("document-save-as"));
84  connect(ui_.save_as_image_push_button, SIGNAL(pressed()), this, SLOT(saveImage()));
85 
86  connect(ui_.num_gridlines_spin_box, SIGNAL(valueChanged(int)), this, SLOT(updateNumGridlines()));
87 
88  // set topic name if passed in as argument
89  const QStringList& argv = context.argv();
90  if (!argv.empty()) {
91  arg_topic_name = argv[0];
93  }
94  pub_topic_custom_ = false;
95 
96  ui_.image_frame->setOuterLayout(ui_.image_layout);
97 
98  QRegExp rx("([a-zA-Z/][a-zA-Z0-9_/]*)?"); //see http://www.ros.org/wiki/ROS/Concepts#Names.Valid_Names (but also accept an empty field)
99  ui_.publish_click_location_topic_line_edit->setValidator(new QRegExpValidator(rx, this));
100  connect(ui_.publish_click_location_check_box, SIGNAL(toggled(bool)), this, SLOT(onMousePublish(bool)));
101  connect(ui_.image_frame, SIGNAL(mouseLeft(int, int)), this, SLOT(onMouseLeft(int, int)));
102  connect(ui_.publish_click_location_topic_line_edit, SIGNAL(editingFinished()), this, SLOT(onPubTopicChanged()));
103 
104  connect(ui_.smooth_image_check_box, SIGNAL(toggled(bool)), ui_.image_frame, SLOT(onSmoothImageChanged(bool)));
105 
106  connect(ui_.rotate_left_push_button, SIGNAL(clicked(bool)), this, SLOT(onRotateLeft()));
107  connect(ui_.rotate_right_push_button, SIGNAL(clicked(bool)), this, SLOT(onRotateRight()));
108 
109  // Make sure we have enough space for "XXX °"
110  ui_.rotate_label->setMinimumWidth(
111  ui_.rotate_label->fontMetrics().width("XXX°")
112  );
113 
114  hide_toolbar_action_ = new QAction(tr("Hide toolbar"), this);
115  hide_toolbar_action_->setCheckable(true);
116  ui_.image_frame->addAction(hide_toolbar_action_);
117  connect(hide_toolbar_action_, SIGNAL(toggled(bool)), this, SLOT(onHideToolbarChanged(bool)));
118 }
119 
121 {
124 }
125 
126 void ImageView::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
127 {
128  QString topic = ui_.topics_combo_box->currentText();
129  //qDebug("ImageView::saveSettings() topic '%s'", topic.toStdString().c_str());
130  instance_settings.setValue("topic", topic);
131  instance_settings.setValue("zoom1", ui_.zoom_1_push_button->isChecked());
132  instance_settings.setValue("dynamic_range", ui_.dynamic_range_check_box->isChecked());
133  instance_settings.setValue("max_range", ui_.max_range_double_spin_box->value());
134  instance_settings.setValue("publish_click_location", ui_.publish_click_location_check_box->isChecked());
135  instance_settings.setValue("mouse_pub_topic", ui_.publish_click_location_topic_line_edit->text());
136  instance_settings.setValue("toolbar_hidden", hide_toolbar_action_->isChecked());
137  instance_settings.setValue("num_gridlines", ui_.num_gridlines_spin_box->value());
138  instance_settings.setValue("smooth_image", ui_.smooth_image_check_box->isChecked());
139  instance_settings.setValue("rotate", rotate_state_);
140  instance_settings.setValue("color_scheme", ui_.color_scheme_combo_box->currentIndex());
141 }
142 
143 void ImageView::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
144 {
145  bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
146  ui_.zoom_1_push_button->setChecked(zoom1_checked);
147 
148  bool dynamic_range_checked = instance_settings.value("dynamic_range", false).toBool();
149  ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
150 
151  double max_range = instance_settings.value("max_range", ui_.max_range_double_spin_box->value()).toDouble();
152  ui_.max_range_double_spin_box->setValue(max_range);
153 
154  num_gridlines_ = instance_settings.value("num_gridlines", ui_.num_gridlines_spin_box->value()).toInt();
155  ui_.num_gridlines_spin_box->setValue(num_gridlines_);
156 
157  QString topic = instance_settings.value("topic", "").toString();
158  // don't overwrite topic name passed as command line argument
159  if (!arg_topic_name.isEmpty())
160  {
161  arg_topic_name = "";
162  }
163  else
164  {
165  //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str());
166  selectTopic(topic);
167  }
168 
169  bool publish_click_location = instance_settings.value("publish_click_location", false).toBool();
170  ui_.publish_click_location_check_box->setChecked(publish_click_location);
171 
172  QString pub_topic = instance_settings.value("mouse_pub_topic", "").toString();
173  ui_.publish_click_location_topic_line_edit->setText(pub_topic);
174 
175  bool toolbar_hidden = instance_settings.value("toolbar_hidden", false).toBool();
176  hide_toolbar_action_->setChecked(toolbar_hidden);
177 
178  bool smooth_image_checked = instance_settings.value("smooth_image", false).toBool();
179  ui_.smooth_image_check_box->setChecked(smooth_image_checked);
180 
181  rotate_state_ = static_cast<RotateState>(instance_settings.value("rotate", 0).toInt());
184  syncRotateLabel();
185 
186  int color_scheme = instance_settings.value("color_scheme", ui_.color_scheme_combo_box->currentIndex()).toInt();
187  ui_.color_scheme_combo_box->setCurrentIndex(color_scheme);
188 }
189 
191 {
192  static const std::map<std::string, int> COLOR_SCHEME_MAP
193  {
194  { "Gray", -1 }, // Special case: no color map
195  { "Autumn", cv::COLORMAP_AUTUMN },
196  { "Bone", cv::COLORMAP_BONE },
197  { "Cool", cv::COLORMAP_COOL },
198  { "Hot", cv::COLORMAP_HOT },
199  { "Hsv", cv::COLORMAP_HSV },
200  { "Jet", cv::COLORMAP_JET },
201  { "Ocean", cv::COLORMAP_OCEAN },
202  { "Pink", cv::COLORMAP_PINK },
203  { "Rainbow", cv::COLORMAP_RAINBOW },
204  { "Spring", cv::COLORMAP_SPRING },
205  { "Summer", cv::COLORMAP_SUMMER },
206  { "Winter", cv::COLORMAP_WINTER }
207  };
208 
209  for (const auto& kv : COLOR_SCHEME_MAP)
210  {
211  ui_.color_scheme_combo_box->addItem(QString::fromStdString(kv.first), QVariant(kv.second));
212  }
213 }
214 
216 {
217  QSet<QString> message_types;
218  message_types.insert("sensor_msgs/Image");
219  QSet<QString> message_sub_types;
220  message_sub_types.insert("sensor_msgs/CompressedImage");
221 
222  // get declared transports
223  QList<QString> transports;
225  std::vector<std::string> declared = it.getDeclaredTransports();
226  for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
227  {
228  //qDebug("ImageView::updateTopicList() declared transport '%s'", it->c_str());
229  QString transport = it->c_str();
230 
231  // strip prefix from transport name
232  QString prefix = "image_transport/";
233  if (transport.startsWith(prefix))
234  {
235  transport = transport.mid(prefix.length());
236  }
237  transports.append(transport);
238  }
239 
240  QString selected = ui_.topics_combo_box->currentText();
241 
242  // fill combo box
243  QList<QString> topics = getTopics(message_types, message_sub_types, transports).values();
244  topics.append("");
245  qSort(topics);
246  ui_.topics_combo_box->clear();
247  for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
248  {
249  QString label(*it);
250  label.replace(" ", "/");
251  ui_.topics_combo_box->addItem(label, QVariant(*it));
252  }
253 
254  // restore previous selection
255  selectTopic(selected);
256 }
257 
258 QList<QString> ImageView::getTopicList(const QSet<QString>& message_types, const QList<QString>& transports)
259 {
260  QSet<QString> message_sub_types;
261  return getTopics(message_types, message_sub_types, transports).values();
262 }
263 
264 QSet<QString> ImageView::getTopics(const QSet<QString>& message_types, const QSet<QString>& message_sub_types, const QList<QString>& transports)
265 {
266  ros::master::V_TopicInfo topic_info;
267  ros::master::getTopics(topic_info);
268 
269  QSet<QString> all_topics;
270  for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
271  {
272  all_topics.insert(it->name.c_str());
273  }
274 
275  QSet<QString> topics;
276  for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
277  {
278  if (message_types.contains(it->datatype.c_str()))
279  {
280  QString topic = it->name.c_str();
281 
282  // add raw topic
283  topics.insert(topic);
284  //qDebug("ImageView::getTopics() raw topic '%s'", topic.toStdString().c_str());
285 
286  // add transport specific sub-topics
287  for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
288  {
289  if (all_topics.contains(topic + "/" + *jt))
290  {
291  QString sub = topic + " " + *jt;
292  topics.insert(sub);
293  //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", sub.toStdString().c_str());
294  }
295  }
296  }
297  if (message_sub_types.contains(it->datatype.c_str()))
298  {
299  QString topic = it->name.c_str();
300  int index = topic.lastIndexOf("/");
301  if (index != -1)
302  {
303  topic.replace(index, 1, " ");
304  topics.insert(topic);
305  //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", topic.toStdString().c_str());
306  }
307  }
308  }
309  return topics;
310 }
311 
312 void ImageView::selectTopic(const QString& topic)
313 {
314  int index = ui_.topics_combo_box->findText(topic);
315  if (index == -1)
316  {
317  // add topic name to list if not yet in
318  QString label(topic);
319  label.replace(" ", "/");
320  ui_.topics_combo_box->addItem(label, QVariant(topic));
321  index = ui_.topics_combo_box->findText(topic);
322  }
323  ui_.topics_combo_box->setCurrentIndex(index);
324 }
325 
327 {
328  conversion_mat_.release();
329 
331 
332  // reset image on topic change
333  ui_.image_frame->setImage(QImage());
334 
335  QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" ");
336  QString topic = parts.first();
337  QString transport = parts.length() == 2 ? parts.last() : "raw";
338 
339  if (!topic.isEmpty())
340  {
342  image_transport::TransportHints hints(transport.toStdString());
343  try {
344  subscriber_ = it.subscribe(topic.toStdString(), 1, &ImageView::callbackImage, this, hints);
345  //qDebug("ImageView::onTopicChanged() to topic '%s' with transport '%s'", topic.toStdString().c_str(), subscriber_.getTransport().c_str());
347  QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what());
348  }
349  }
350 
351  onMousePublish(ui_.publish_click_location_check_box->isChecked());
352 }
353 
354 void ImageView::onZoom1(bool checked)
355 {
356  if (checked)
357  {
358  if (ui_.image_frame->getImage().isNull())
359  {
360  return;
361  }
362  ui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size());
363  } else {
364  ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
365  ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
366  widget_->setMinimumSize(QSize(80, 60));
367  widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
368  }
369 }
370 
371 void ImageView::onDynamicRange(bool checked)
372 {
373  ui_.max_range_double_spin_box->setEnabled(!checked);
374 }
375 
377 {
378  num_gridlines_ = ui_.num_gridlines_spin_box->value();
379 }
380 
382 {
383  // take a snapshot before asking for the filename
384  QImage img = ui_.image_frame->getImageCopy();
385 
386  QString file_name = QFileDialog::getSaveFileName(widget_, tr("Save as image"), "image.png", tr("Image (*.bmp *.jpg *.png *.tiff)"));
387  if (file_name.isEmpty())
388  {
389  return;
390  }
391 
392  img.save(file_name);
393 }
394 
395 void ImageView::onMousePublish(bool checked)
396 {
397  std::string topicName;
399  {
400  topicName = ui_.publish_click_location_topic_line_edit->text().toStdString();
401  } else {
402  if(!subscriber_.getTopic().empty())
403  {
404  topicName = subscriber_.getTopic()+"_mouse_left";
405  } else {
406  topicName = "mouse_left";
407  }
408  ui_.publish_click_location_topic_line_edit->setText(QString::fromStdString(topicName));
409  }
410 
411  if(checked)
412  {
413  pub_mouse_left_ = getNodeHandle().advertise<geometry_msgs::Point>(topicName, 1000);
414  } else {
416  }
417 }
418 
419 void ImageView::onMouseLeft(int x, int y)
420 {
421  if(ui_.publish_click_location_check_box->isChecked() && !ui_.image_frame->getImage().isNull())
422  {
423  geometry_msgs::Point clickCanvasLocation;
424  // Publish click location in pixel coordinates
425  clickCanvasLocation.x = round((double)x/(double)ui_.image_frame->width()*(double)ui_.image_frame->getImage().width());
426  clickCanvasLocation.y = round((double)y/(double)ui_.image_frame->height()*(double)ui_.image_frame->getImage().height());
427  clickCanvasLocation.z = 0;
428 
429  geometry_msgs::Point clickLocation = clickCanvasLocation;
430 
431  switch(rotate_state_)
432  {
433  case ROTATE_90:
434  clickLocation.x = clickCanvasLocation.y;
435  clickLocation.y = ui_.image_frame->getImage().width() - clickCanvasLocation.x;
436  break;
437  case ROTATE_180:
438  clickLocation.x = ui_.image_frame->getImage().width() - clickCanvasLocation.x;
439  clickLocation.y = ui_.image_frame->getImage().height() - clickCanvasLocation.y;
440  break;
441  case ROTATE_270:
442  clickLocation.x = ui_.image_frame->getImage().height() - clickCanvasLocation.y;
443  clickLocation.y = clickCanvasLocation.x;
444  break;
445  default:
446  break;
447  }
448 
449  pub_mouse_left_.publish(clickLocation);
450  }
451 }
452 
454 {
455  pub_topic_custom_ = !(ui_.publish_click_location_topic_line_edit->text().isEmpty());
456  onMousePublish(ui_.publish_click_location_check_box->isChecked());
457 }
458 
460 {
461  ui_.toolbar_widget->setVisible(!hide);
462 }
463 
465 {
466  int m = rotate_state_ - 1;
467  if(m < 0)
468  m = ROTATE_STATE_COUNT-1;
469 
470  rotate_state_ = static_cast<RotateState>(m);
471  syncRotateLabel();
472 }
473 
475 {
477  syncRotateLabel();
478 }
479 
481 {
482  switch(rotate_state_)
483  {
484  default:
485  case ROTATE_0: ui_.rotate_label->setText("0°"); break;
486  case ROTATE_90: ui_.rotate_label->setText("90°"); break;
487  case ROTATE_180: ui_.rotate_label->setText("180°"); break;
488  case ROTATE_270: ui_.rotate_label->setText("270°"); break;
489  }
490 }
491 
492 void ImageView::invertPixels(int x, int y)
493 {
494  // Could do 255-conversion_mat_.at<cv::Vec3b>(cv::Point(x,y))[i], but that doesn't work well on gray
495  cv::Vec3b & pixel = conversion_mat_.at<cv::Vec3b>(cv::Point(x, y));
496  if (pixel[0] + pixel[1] + pixel[2] > 3 * 127)
497  pixel = cv::Vec3b(0,0,0);
498  else
499  pixel = cv::Vec3b(255,255,255);
500 }
501 
502 QList<int> ImageView::getGridIndices(int size) const
503 {
504  QList<int> indices;
505 
506  // the spacing between adjacent grid lines
507  float grid_width = 1.0f * size / (num_gridlines_ + 1);
508 
509  // select grid line(s) closest to the center
510  float index;
511  if (num_gridlines_ % 2) // odd
512  {
513  indices.append(size / 2);
514  // make the center line 2px wide in case of an even resolution
515  if (size % 2 == 0) // even
516  indices.append(size / 2 - 1);
517  index = 1.0f * (size - 1) / 2;
518  }
519  else // even
520  {
521  index = grid_width * (num_gridlines_ / 2);
522  // one grid line before the center
523  indices.append(round(index));
524  // one grid line after the center
525  indices.append(size - 1 - round(index));
526  }
527 
528  // add additional grid lines from the center to the border of the image
529  int lines = (num_gridlines_ - 1) / 2;
530  while (lines > 0)
531  {
532  index -= grid_width;
533  indices.append(round(index));
534  indices.append(size - 1 - round(index));
535  lines--;
536  }
537 
538  return indices;
539 }
540 
542 {
543  // vertical gridlines
544  QList<int> columns = getGridIndices(conversion_mat_.cols);
545  for (QList<int>::const_iterator x = columns.begin(); x != columns.end(); ++x)
546  {
547  for (int y = 0; y < conversion_mat_.rows; ++y)
548  {
549  invertPixels(*x, y);
550  }
551  }
552 
553  // horizontal gridlines
554  QList<int> rows = getGridIndices(conversion_mat_.rows);
555  for (QList<int>::const_iterator y = rows.begin(); y != rows.end(); ++y)
556  {
557  for (int x = 0; x < conversion_mat_.cols; ++x)
558  {
559  invertPixels(x, *y);
560  }
561  }
562 }
563 
564 void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
565 {
566  try
567  {
568  // First let cv_bridge do its magic
570  conversion_mat_ = cv_ptr->image;
571 
572  if (num_gridlines_ > 0)
573  overlayGrid();
574  }
575  catch (cv_bridge::Exception& e)
576  {
577  try
578  {
579  // If we're here, there is no conversion that makes sense, but let's try to imagine a few first
581  if (msg->encoding == "CV_8UC3")
582  {
583  // assuming it is rgb
584  conversion_mat_ = cv_ptr->image;
585  } else if (msg->encoding == "8UC1") {
586  // convert gray to rgb
587  cv::cvtColor(cv_ptr->image, conversion_mat_, CV_GRAY2RGB);
588  } else if (msg->encoding == "16UC1" || msg->encoding == "32FC1") {
589  // scale / quantify
590  double min = 0;
591  double max = ui_.max_range_double_spin_box->value();
592  if (msg->encoding == "16UC1") max *= 1000;
593  if (ui_.dynamic_range_check_box->isChecked())
594  {
595  // dynamically adjust range based on min/max in image
596  cv::minMaxLoc(cv_ptr->image, &min, &max);
597  if (min == max) {
598  // completely homogeneous images are displayed in gray
599  min = 0;
600  max = 2;
601  }
602  }
603  cv::Mat img_scaled_8u;
604  cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
605 
606  const auto color_scheme_index = ui_.color_scheme_combo_box->currentIndex();
607  const auto color_scheme = ui_.color_scheme_combo_box->itemData(color_scheme_index).toInt();
608  if (color_scheme == -1) {
609  cv::cvtColor(img_scaled_8u, conversion_mat_, CV_GRAY2RGB);
610  } else {
611  cv::Mat img_color_scheme;
612  cv::applyColorMap(img_scaled_8u, img_color_scheme, color_scheme);
613  cv::cvtColor(img_color_scheme, conversion_mat_, CV_BGR2RGB);
614  }
615  } else {
616  qWarning("ImageView.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
617  ui_.image_frame->setImage(QImage());
618  return;
619  }
620  }
621  catch (cv_bridge::Exception& e)
622  {
623  qWarning("ImageView.callback_image() while trying to convert image from '%s' to 'rgb8' an exception was thrown (%s)", msg->encoding.c_str(), e.what());
624  ui_.image_frame->setImage(QImage());
625  return;
626  }
627  }
628 
629  // Handle rotation
630  switch(rotate_state_)
631  {
632  case ROTATE_90:
633  {
634  cv::Mat tmp;
635  cv::transpose(conversion_mat_, tmp);
636  cv::flip(tmp, conversion_mat_, 1);
637  break;
638  }
639  case ROTATE_180:
640  {
641  cv::Mat tmp;
642  cv::flip(conversion_mat_, tmp, -1);
643  conversion_mat_ = tmp;
644  break;
645  }
646  case ROTATE_270:
647  {
648  cv::Mat tmp;
649  cv::transpose(conversion_mat_, tmp);
650  cv::flip(tmp, conversion_mat_, 0);
651  break;
652  }
653  default:
654  break;
655  }
656 
657  // image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
658  QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, conversion_mat_.step[0], QImage::Format_RGB888);
659  ui_.image_frame->setImage(image);
660 
661  if (!ui_.zoom_1_push_button->isEnabled())
662  {
663  ui_.zoom_1_push_button->setEnabled(true);
664  }
665  // Need to update the zoom 1 every new image in case the image aspect ratio changed,
666  // though could check and see if the aspect ratio changed or not.
667  onZoom1(ui_.zoom_1_push_button->isChecked());
668 }
669 }
670 
rqt_image_view
Definition: image_view.h:58
rqt_image_view::ImageView::ROTATE_STATE_COUNT
@ ROTATE_STATE_COUNT
Definition: image_view.h:142
rqt_image_view::ImageView::widget_
QWidget * widget_
Definition: image_view.h:128
image_transport::ImageTransport::getDeclaredTransports
std::vector< std::string > getDeclaredTransports() const
rqt_image_view::ImageView
Definition: image_view.h:60
rqt_image_view::ImageView::initPlugin
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Definition: image_view.cpp:57
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
rqt_image_view::ImageView::ROTATE_0
@ ROTATE_0
Definition: image_view.h:137
rqt_image_view::ImageView::getTopicList
virtual ROS_DEPRECATED QList< QString > getTopicList(const QSet< QString > &message_types, const QList< QString > &transports)
Definition: image_view.cpp:258
image_transport::ImageTransport
qt_gui_cpp::Settings::setValue
void setValue(const QString &key, const QVariant &value)
rqt_image_view::ImageView::getTopics
virtual QSet< QString > getTopics(const QSet< QString > &message_types, const QSet< QString > &message_sub_types, const QList< QString > &transports)
Definition: image_view.cpp:264
rqt_image_view::ImageView::subscriber_
image_transport::Subscriber subscriber_
Definition: image_view.h:130
boost::shared_ptr
rqt_image_view::ImageView::callbackImage
virtual void callbackImage(const sensor_msgs::Image::ConstPtr &msg)
Definition: image_view.cpp:564
qt_gui_cpp::PluginContext
rqt_image_view::ImageView::pub_mouse_left_
ros::Publisher pub_mouse_left_
Definition: image_view.h:148
rqt_image_view::ImageView::onMousePublish
virtual void onMousePublish(bool checked)
Definition: image_view.cpp:395
qt_gui_cpp::PluginContext::addWidget
void addWidget(QWidget *widget)
rqt_image_view::ImageView::arg_topic_name
QString arg_topic_name
Definition: image_view.h:147
cv_bridge::Exception
rqt_image_view::ImageView::ui_
Ui::ImageViewWidget ui_
Definition: image_view.h:126
sensor_msgs::image_encodings::RGB8
const std::string RGB8
rqt_image_view::ImageView::onDynamicRange
virtual void onDynamicRange(bool checked)
Definition: image_view.cpp:371
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
rqt_image_view::ImageView::ROTATE_180
@ ROTATE_180
Definition: image_view.h:139
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
rqt_image_view::ImageView::saveImage
virtual void saveImage()
Definition: image_view.cpp:381
qt_gui_cpp::Settings
image_transport::TransportLoadException
rqt_image_view::ImageView::onZoom1
virtual void onZoom1(bool checked)
Definition: image_view.cpp:354
rqt_image_view::ImageView::syncRotateLabel
void syncRotateLabel()
Definition: image_view.cpp:480
rqt_gui_cpp::Plugin
rqt_gui_cpp
rqt_image_view::ImageView::ROTATE_90
@ ROTATE_90
Definition: image_view.h:138
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Publisher::shutdown
void shutdown()
rqt_image_view::ImageView::conversion_mat_
cv::Mat conversion_mat_
Definition: image_view.h:132
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
rqt_image_view::ImageView::onRotateRight
virtual void onRotateRight()
Definition: image_view.cpp:474
rqt_image_view::ImageView::num_gridlines_
int num_gridlines_
Definition: image_view.h:154
rqt_image_view::ImageView::onRotateLeft
virtual void onRotateLeft()
Definition: image_view.cpp:464
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
rqt_image_view::ImageView::onTopicChanged
virtual void onTopicChanged(int index)
Definition: image_view.cpp:326
rqt_image_view::ImageView::shutdownPlugin
virtual void shutdownPlugin()
Definition: image_view.cpp:120
qt_gui_cpp::PluginContext::argv
const QStringList & argv() const
rqt_image_view::ImageView::rotate_state_
RotateState rotate_state_
Definition: image_view.h:156
rqt_image_view::ImageView::updateTopicList
virtual void updateTopicList()
Definition: image_view.cpp:215
qt_gui_cpp::PluginContext::serialNumber
int serialNumber() const
rqt_image_view::ImageView::selectTopic
virtual void selectTopic(const QString &topic)
Definition: image_view.cpp:312
rqt_image_view::ImageView::overlayGrid
virtual void overlayGrid()
Definition: image_view.cpp:541
rqt_image_view::ImageView::restoreSettings
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
Definition: image_view.cpp:143
cv_bridge.h
class_list_macros.hpp
rqt_image_view::ImageView::saveSettings
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
Definition: image_view.cpp:126
rqt_image_view::ImageView::invertPixels
virtual void invertPixels(int x, int y)
Definition: image_view.cpp:492
rqt_image_view::ImageView::RotateState
RotateState
Definition: image_view.h:136
rqt_image_view::ImageView::getGridIndices
QList< int > getGridIndices(int size) const
Definition: image_view.cpp:502
image_view.h
rqt_image_view::ImageView::ImageView
ImageView()
Definition: image_view.cpp:48
image_transport::TransportHints
rqt_image_view::ImageView::onHideToolbarChanged
virtual void onHideToolbarChanged(bool hide)
Definition: image_view.cpp:459
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
rqt_image_view::ImageView::updateNumGridlines
virtual void updateNumGridlines()
Definition: image_view.cpp:376
qt_gui_cpp::Settings::value
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const
rqt_image_view::ImageView::ROTATE_270
@ ROTATE_270
Definition: image_view.h:140
master.h
rqt_image_view::ImageView::pub_topic_custom_
bool pub_topic_custom_
Definition: image_view.h:150
image_transport::Subscriber::getTopic
std::string getTopic() const
rqt_image_view::ImageView::onMouseLeft
virtual void onMouseLeft(int x, int y)
Definition: image_view.cpp:419
rqt_image_view::ImageView::onPubTopicChanged
virtual void onPubTopicChanged()
Definition: image_view.cpp:453
rqt_image_view::ImageView::hide_toolbar_action_
QAction * hide_toolbar_action_
Definition: image_view.h:152
rqt_image_view::ImageView::setColorSchemeList
virtual void setColorSchemeList()
Definition: image_view.cpp:190
image_transport::Subscriber::shutdown
void shutdown()


rqt_image_view
Author(s): Dirk Thomas , Mabel Zhang
autogenerated on Fri May 26 2023 02:31:55