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 }
141 
142 void ImageView::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
143 {
144  bool zoom1_checked = instance_settings.value("zoom1", false).toBool();
145  ui_.zoom_1_push_button->setChecked(zoom1_checked);
146 
147  bool dynamic_range_checked = instance_settings.value("dynamic_range", false).toBool();
148  ui_.dynamic_range_check_box->setChecked(dynamic_range_checked);
149 
150  double max_range = instance_settings.value("max_range", ui_.max_range_double_spin_box->value()).toDouble();
151  ui_.max_range_double_spin_box->setValue(max_range);
152 
153  num_gridlines_ = instance_settings.value("num_gridlines", ui_.num_gridlines_spin_box->value()).toInt();
154  ui_.num_gridlines_spin_box->setValue(num_gridlines_);
155 
156  QString topic = instance_settings.value("topic", "").toString();
157  // don't overwrite topic name passed as command line argument
158  if (!arg_topic_name.isEmpty())
159  {
160  arg_topic_name = "";
161  }
162  else
163  {
164  //qDebug("ImageView::restoreSettings() topic '%s'", topic.toStdString().c_str());
165  selectTopic(topic);
166  }
167 
168  bool publish_click_location = instance_settings.value("publish_click_location", false).toBool();
169  ui_.publish_click_location_check_box->setChecked(publish_click_location);
170 
171  QString pub_topic = instance_settings.value("mouse_pub_topic", "").toString();
172  ui_.publish_click_location_topic_line_edit->setText(pub_topic);
173 
174  bool toolbar_hidden = instance_settings.value("toolbar_hidden", false).toBool();
175  hide_toolbar_action_->setChecked(toolbar_hidden);
176 
177  bool smooth_image_checked = instance_settings.value("smooth_image", false).toBool();
178  ui_.smooth_image_check_box->setChecked(smooth_image_checked);
179 
180  rotate_state_ = static_cast<RotateState>(instance_settings.value("rotate", 0).toInt());
183  syncRotateLabel();
184 }
185 
187 {
188  static const std::map<std::string, int> COLOR_SCHEME_MAP
189  {
190  { "Gray", -1 }, // Special case: no color map
191  { "Autumn", cv::COLORMAP_AUTUMN },
192  { "Bone", cv::COLORMAP_BONE },
193  { "Cool", cv::COLORMAP_COOL },
194  { "Hot", cv::COLORMAP_HOT },
195  { "Hsv", cv::COLORMAP_HSV },
196  { "Jet", cv::COLORMAP_JET },
197  { "Ocean", cv::COLORMAP_OCEAN },
198  { "Pink", cv::COLORMAP_PINK },
199  { "Rainbow", cv::COLORMAP_RAINBOW },
200  { "Spring", cv::COLORMAP_SPRING },
201  { "Summer", cv::COLORMAP_SUMMER },
202  { "Winter", cv::COLORMAP_WINTER }
203  };
204 
205  for (const auto& kv : COLOR_SCHEME_MAP)
206  {
207  ui_.color_scheme_combo_box->addItem(QString::fromStdString(kv.first), QVariant(kv.second));
208  }
209 }
210 
212 {
213  QSet<QString> message_types;
214  message_types.insert("sensor_msgs/Image");
215  QSet<QString> message_sub_types;
216  message_sub_types.insert("sensor_msgs/CompressedImage");
217 
218  // get declared transports
219  QList<QString> transports;
221  std::vector<std::string> declared = it.getDeclaredTransports();
222  for (std::vector<std::string>::const_iterator it = declared.begin(); it != declared.end(); it++)
223  {
224  //qDebug("ImageView::updateTopicList() declared transport '%s'", it->c_str());
225  QString transport = it->c_str();
226 
227  // strip prefix from transport name
228  QString prefix = "image_transport/";
229  if (transport.startsWith(prefix))
230  {
231  transport = transport.mid(prefix.length());
232  }
233  transports.append(transport);
234  }
235 
236  QString selected = ui_.topics_combo_box->currentText();
237 
238  // fill combo box
239  QList<QString> topics = getTopics(message_types, message_sub_types, transports).values();
240  topics.append("");
241  qSort(topics);
242  ui_.topics_combo_box->clear();
243  for (QList<QString>::const_iterator it = topics.begin(); it != topics.end(); it++)
244  {
245  QString label(*it);
246  label.replace(" ", "/");
247  ui_.topics_combo_box->addItem(label, QVariant(*it));
248  }
249 
250  // restore previous selection
251  selectTopic(selected);
252 }
253 
254 QList<QString> ImageView::getTopicList(const QSet<QString>& message_types, const QList<QString>& transports)
255 {
256  QSet<QString> message_sub_types;
257  return getTopics(message_types, message_sub_types, transports).values();
258 }
259 
260 QSet<QString> ImageView::getTopics(const QSet<QString>& message_types, const QSet<QString>& message_sub_types, const QList<QString>& transports)
261 {
262  ros::master::V_TopicInfo topic_info;
263  ros::master::getTopics(topic_info);
264 
265  QSet<QString> all_topics;
266  for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
267  {
268  all_topics.insert(it->name.c_str());
269  }
270 
271  QSet<QString> topics;
272  for (ros::master::V_TopicInfo::const_iterator it = topic_info.begin(); it != topic_info.end(); it++)
273  {
274  if (message_types.contains(it->datatype.c_str()))
275  {
276  QString topic = it->name.c_str();
277 
278  // add raw topic
279  topics.insert(topic);
280  //qDebug("ImageView::getTopics() raw topic '%s'", topic.toStdString().c_str());
281 
282  // add transport specific sub-topics
283  for (QList<QString>::const_iterator jt = transports.begin(); jt != transports.end(); jt++)
284  {
285  if (all_topics.contains(topic + "/" + *jt))
286  {
287  QString sub = topic + " " + *jt;
288  topics.insert(sub);
289  //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", sub.toStdString().c_str());
290  }
291  }
292  }
293  if (message_sub_types.contains(it->datatype.c_str()))
294  {
295  QString topic = it->name.c_str();
296  int index = topic.lastIndexOf("/");
297  if (index != -1)
298  {
299  topic.replace(index, 1, " ");
300  topics.insert(topic);
301  //qDebug("ImageView::getTopics() transport specific sub-topic '%s'", topic.toStdString().c_str());
302  }
303  }
304  }
305  return topics;
306 }
307 
308 void ImageView::selectTopic(const QString& topic)
309 {
310  int index = ui_.topics_combo_box->findText(topic);
311  if (index == -1)
312  {
313  // add topic name to list if not yet in
314  QString label(topic);
315  label.replace(" ", "/");
316  ui_.topics_combo_box->addItem(label, QVariant(topic));
317  index = ui_.topics_combo_box->findText(topic);
318  }
319  ui_.topics_combo_box->setCurrentIndex(index);
320 }
321 
323 {
324  conversion_mat_.release();
325 
327 
328  // reset image on topic change
329  ui_.image_frame->setImage(QImage());
330 
331  QStringList parts = ui_.topics_combo_box->itemData(index).toString().split(" ");
332  QString topic = parts.first();
333  QString transport = parts.length() == 2 ? parts.last() : "raw";
334 
335  if (!topic.isEmpty())
336  {
338  image_transport::TransportHints hints(transport.toStdString());
339  try {
340  subscriber_ = it.subscribe(topic.toStdString(), 1, &ImageView::callbackImage, this, hints);
341  //qDebug("ImageView::onTopicChanged() to topic '%s' with transport '%s'", topic.toStdString().c_str(), subscriber_.getTransport().c_str());
343  QMessageBox::warning(widget_, tr("Loading image transport plugin failed"), e.what());
344  }
345  }
346 
347  onMousePublish(ui_.publish_click_location_check_box->isChecked());
348 }
349 
350 void ImageView::onZoom1(bool checked)
351 {
352  if (checked)
353  {
354  if (ui_.image_frame->getImage().isNull())
355  {
356  return;
357  }
358  ui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size());
359  } else {
360  ui_.image_frame->setInnerFrameMinimumSize(QSize(80, 60));
361  ui_.image_frame->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
362  widget_->setMinimumSize(QSize(80, 60));
363  widget_->setMaximumSize(QSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX));
364  }
365 }
366 
367 void ImageView::onDynamicRange(bool checked)
368 {
369  ui_.max_range_double_spin_box->setEnabled(!checked);
370 }
371 
373 {
374  num_gridlines_ = ui_.num_gridlines_spin_box->value();
375 }
376 
378 {
379  // take a snapshot before asking for the filename
380  QImage img = ui_.image_frame->getImageCopy();
381 
382  QString file_name = QFileDialog::getSaveFileName(widget_, tr("Save as image"), "image.png", tr("Image (*.bmp *.jpg *.png *.tiff)"));
383  if (file_name.isEmpty())
384  {
385  return;
386  }
387 
388  img.save(file_name);
389 }
390 
391 void ImageView::onMousePublish(bool checked)
392 {
393  std::string topicName;
395  {
396  topicName = ui_.publish_click_location_topic_line_edit->text().toStdString();
397  } else {
398  if(!subscriber_.getTopic().empty())
399  {
400  topicName = subscriber_.getTopic()+"_mouse_left";
401  } else {
402  topicName = "mouse_left";
403  }
404  ui_.publish_click_location_topic_line_edit->setText(QString::fromStdString(topicName));
405  }
406 
407  if(checked)
408  {
409  pub_mouse_left_ = getNodeHandle().advertise<geometry_msgs::Point>(topicName, 1000);
410  } else {
412  }
413 }
414 
415 void ImageView::onMouseLeft(int x, int y)
416 {
417  if(ui_.publish_click_location_check_box->isChecked() && !ui_.image_frame->getImage().isNull())
418  {
419  geometry_msgs::Point clickCanvasLocation;
420  // Publish click location in pixel coordinates
421  clickCanvasLocation.x = round((double)x/(double)ui_.image_frame->width()*(double)ui_.image_frame->getImage().width());
422  clickCanvasLocation.y = round((double)y/(double)ui_.image_frame->height()*(double)ui_.image_frame->getImage().height());
423  clickCanvasLocation.z = 0;
424 
425  geometry_msgs::Point clickLocation = clickCanvasLocation;
426 
427  switch(rotate_state_)
428  {
429  case ROTATE_90:
430  clickLocation.x = clickCanvasLocation.y;
431  clickLocation.y = ui_.image_frame->getImage().width() - clickCanvasLocation.x;
432  break;
433  case ROTATE_180:
434  clickLocation.x = ui_.image_frame->getImage().width() - clickCanvasLocation.x;
435  clickLocation.y = ui_.image_frame->getImage().height() - clickCanvasLocation.y;
436  break;
437  case ROTATE_270:
438  clickLocation.x = ui_.image_frame->getImage().height() - clickCanvasLocation.y;
439  clickLocation.y = clickCanvasLocation.x;
440  break;
441  default:
442  break;
443  }
444 
445  pub_mouse_left_.publish(clickLocation);
446  }
447 }
448 
450 {
451  pub_topic_custom_ = !(ui_.publish_click_location_topic_line_edit->text().isEmpty());
452  onMousePublish(ui_.publish_click_location_check_box->isChecked());
453 }
454 
456 {
457  ui_.toolbar_widget->setVisible(!hide);
458 }
459 
461 {
462  int m = rotate_state_ - 1;
463  if(m < 0)
464  m = ROTATE_STATE_COUNT-1;
465 
466  rotate_state_ = static_cast<RotateState>(m);
467  syncRotateLabel();
468 }
469 
471 {
473  syncRotateLabel();
474 }
475 
477 {
478  switch(rotate_state_)
479  {
480  default:
481  case ROTATE_0: ui_.rotate_label->setText("0°"); break;
482  case ROTATE_90: ui_.rotate_label->setText("90°"); break;
483  case ROTATE_180: ui_.rotate_label->setText("180°"); break;
484  case ROTATE_270: ui_.rotate_label->setText("270°"); break;
485  }
486 }
487 
488 void ImageView::invertPixels(int x, int y)
489 {
490  // Could do 255-conversion_mat_.at<cv::Vec3b>(cv::Point(x,y))[i], but that doesn't work well on gray
491  cv::Vec3b & pixel = conversion_mat_.at<cv::Vec3b>(cv::Point(x, y));
492  if (pixel[0] + pixel[1] + pixel[2] > 3 * 127)
493  pixel = cv::Vec3b(0,0,0);
494  else
495  pixel = cv::Vec3b(255,255,255);
496 }
497 
498 QList<int> ImageView::getGridIndices(int size) const
499 {
500  QList<int> indices;
501 
502  // the spacing between adjacent grid lines
503  float grid_width = 1.0f * size / (num_gridlines_ + 1);
504 
505  // select grid line(s) closest to the center
506  float index;
507  if (num_gridlines_ % 2) // odd
508  {
509  indices.append(size / 2);
510  // make the center line 2px wide in case of an even resolution
511  if (size % 2 == 0) // even
512  indices.append(size / 2 - 1);
513  index = 1.0f * (size - 1) / 2;
514  }
515  else // even
516  {
517  index = grid_width * (num_gridlines_ / 2);
518  // one grid line before the center
519  indices.append(round(index));
520  // one grid line after the center
521  indices.append(size - 1 - round(index));
522  }
523 
524  // add additional grid lines from the center to the border of the image
525  int lines = (num_gridlines_ - 1) / 2;
526  while (lines > 0)
527  {
528  index -= grid_width;
529  indices.append(round(index));
530  indices.append(size - 1 - round(index));
531  lines--;
532  }
533 
534  return indices;
535 }
536 
538 {
539  // vertical gridlines
540  QList<int> columns = getGridIndices(conversion_mat_.cols);
541  for (QList<int>::const_iterator x = columns.begin(); x != columns.end(); ++x)
542  {
543  for (int y = 0; y < conversion_mat_.rows; ++y)
544  {
545  invertPixels(*x, y);
546  }
547  }
548 
549  // horizontal gridlines
550  QList<int> rows = getGridIndices(conversion_mat_.rows);
551  for (QList<int>::const_iterator y = rows.begin(); y != rows.end(); ++y)
552  {
553  for (int x = 0; x < conversion_mat_.cols; ++x)
554  {
555  invertPixels(x, *y);
556  }
557  }
558 }
559 
560 void ImageView::callbackImage(const sensor_msgs::Image::ConstPtr& msg)
561 {
562  try
563  {
564  // First let cv_bridge do its magic
566  conversion_mat_ = cv_ptr->image;
567 
568  if (num_gridlines_ > 0)
569  overlayGrid();
570  }
571  catch (cv_bridge::Exception& e)
572  {
573  try
574  {
575  // If we're here, there is no conversion that makes sense, but let's try to imagine a few first
577  if (msg->encoding == "CV_8UC3")
578  {
579  // assuming it is rgb
580  conversion_mat_ = cv_ptr->image;
581  } else if (msg->encoding == "8UC1") {
582  // convert gray to rgb
583  cv::cvtColor(cv_ptr->image, conversion_mat_, CV_GRAY2RGB);
584  } else if (msg->encoding == "16UC1" || msg->encoding == "32FC1") {
585  // scale / quantify
586  double min = 0;
587  double max = ui_.max_range_double_spin_box->value();
588  if (msg->encoding == "16UC1") max *= 1000;
589  if (ui_.dynamic_range_check_box->isChecked())
590  {
591  // dynamically adjust range based on min/max in image
592  cv::minMaxLoc(cv_ptr->image, &min, &max);
593  if (min == max) {
594  // completely homogeneous images are displayed in gray
595  min = 0;
596  max = 2;
597  }
598  }
599  cv::Mat img_scaled_8u;
600  cv::Mat(cv_ptr->image-min).convertTo(img_scaled_8u, CV_8UC1, 255. / (max - min));
601 
602  const auto color_scheme_index = ui_.color_scheme_combo_box->currentIndex();
603  const auto color_scheme = ui_.color_scheme_combo_box->itemData(color_scheme_index).toInt();
604  if (color_scheme == -1) {
605  cv::cvtColor(img_scaled_8u, conversion_mat_, CV_GRAY2RGB);
606  } else {
607  cv::Mat img_color_scheme;
608  cv::applyColorMap(img_scaled_8u, img_color_scheme, color_scheme);
609  cv::cvtColor(img_color_scheme, conversion_mat_, CV_BGR2RGB);
610  }
611  } else {
612  qWarning("ImageView.callback_image() could not convert image from '%s' to 'rgb8' (%s)", msg->encoding.c_str(), e.what());
613  ui_.image_frame->setImage(QImage());
614  return;
615  }
616  }
617  catch (cv_bridge::Exception& e)
618  {
619  qWarning("ImageView.callback_image() while trying to convert image from '%s' to 'rgb8' an exception was thrown (%s)", msg->encoding.c_str(), e.what());
620  ui_.image_frame->setImage(QImage());
621  return;
622  }
623  }
624 
625  // Handle rotation
626  switch(rotate_state_)
627  {
628  case ROTATE_90:
629  {
630  cv::Mat tmp;
631  cv::transpose(conversion_mat_, tmp);
632  cv::flip(tmp, conversion_mat_, 1);
633  break;
634  }
635  case ROTATE_180:
636  {
637  cv::Mat tmp;
638  cv::flip(conversion_mat_, tmp, -1);
639  conversion_mat_ = tmp;
640  break;
641  }
642  case ROTATE_270:
643  {
644  cv::Mat tmp;
645  cv::transpose(conversion_mat_, tmp);
646  cv::flip(tmp, conversion_mat_, 0);
647  break;
648  }
649  default:
650  break;
651  }
652 
653  // image must be copied since it uses the conversion_mat_ for storage which is asynchronously overwritten in the next callback invocation
654  QImage image(conversion_mat_.data, conversion_mat_.cols, conversion_mat_.rows, conversion_mat_.step[0], QImage::Format_RGB888);
655  ui_.image_frame->setImage(image);
656 
657  if (!ui_.zoom_1_push_button->isEnabled())
658  {
659  ui_.zoom_1_push_button->setEnabled(true);
660  }
661  // Need to update the zoom 1 every new image in case the image aspect ratio changed,
662  // though could check and see if the aspect ratio changed or not.
663  onZoom1(ui_.zoom_1_push_button->isChecked());
664 }
665 }
666 
virtual void onMouseLeft(int x, int y)
Definition: image_view.cpp:415
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void onPubTopicChanged()
Definition: image_view.cpp:449
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Definition: image_view.cpp:57
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())
QAction * hide_toolbar_action_
Definition: image_view.h:152
virtual QSet< QString > getTopics(const QSet< QString > &message_types, const QSet< QString > &message_sub_types, const QList< QString > &transports)
Definition: image_view.cpp:260
virtual void callbackImage(const sensor_msgs::Image::ConstPtr &msg)
Definition: image_view.cpp:560
ros::Publisher pub_mouse_left_
Definition: image_view.h:148
void publish(const boost::shared_ptr< M > &message) const
virtual ROS_DEPRECATED QList< QString > getTopicList(const QSet< QString > &message_types, const QList< QString > &transports)
Definition: image_view.cpp:254
image_transport::Subscriber subscriber_
Definition: image_view.h:130
virtual void onMousePublish(bool checked)
Definition: image_view.cpp:391
Ui::ImageViewWidget ui_
Definition: image_view.h:126
virtual void onDynamicRange(bool checked)
Definition: image_view.cpp:367
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const
void addWidget(QWidget *widget)
std::vector< TopicInfo > V_TopicInfo
virtual void onZoom1(bool checked)
Definition: image_view.cpp:350
virtual void saveImage()
Definition: image_view.cpp:377
const QStringList & argv() const
virtual void onRotateLeft()
Definition: image_view.cpp:460
virtual void onTopicChanged(int index)
Definition: image_view.cpp:322
virtual void shutdownPlugin()
Definition: image_view.cpp:120
std::string getTopic() const
std::vector< std::string > getDeclaredTransports() const
virtual void onRotateRight()
Definition: image_view.cpp:470
void setValue(const QString &key, const QVariant &value)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
virtual void updateTopicList()
Definition: image_view.cpp:211
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
Definition: image_view.cpp:126
virtual void selectTopic(const QString &topic)
Definition: image_view.cpp:308
virtual void overlayGrid()
Definition: image_view.cpp:537
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
Definition: image_view.cpp:142
virtual void onHideToolbarChanged(bool hide)
Definition: image_view.cpp:455
QList< int > getGridIndices(int size) const
Definition: image_view.cpp:498
virtual void invertPixels(int x, int y)
Definition: image_view.cpp:488
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void updateNumGridlines()
Definition: image_view.cpp:372
virtual void setColorSchemeList()
Definition: image_view.cpp:186


rqt_image_view
Author(s): Dirk Thomas
autogenerated on Sun Dec 13 2020 03:36:07