image_plugin.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 // C++ standard libraries
33 #include <cstdio>
34 #include <vector>
35 
36 // QT libraries
37 #include <QDialog>
38 #include <QGLWidget>
39 
40 // ROS libraries
41 #include <ros/master.h>
43 #include <opencv2/imgproc/imgproc.hpp>
44 
46 
47 // Declare plugin
50 
51 namespace mapviz_plugins
52 {
53  ImagePlugin::ImagePlugin() :
54  config_widget_(new QWidget()),
55  anchor_(TOP_LEFT),
56  units_(PIXELS),
57  offset_x_(0),
58  offset_y_(0),
59  width_(320),
60  height_(240),
61  transport_("default"),
62  has_image_(false),
63  last_width_(0),
64  last_height_(0),
65  original_aspect_ratio_(1.0)
66  {
67  ui_.setupUi(config_widget_);
68 
69  // Set background white
70  QPalette p(config_widget_->palette());
71  p.setColor(QPalette::Background, Qt::white);
72  config_widget_->setPalette(p);
73 
74  // Set status text red
75  QPalette p3(ui_.status->palette());
76  p3.setColor(QPalette::Text, Qt::red);
77  ui_.status->setPalette(p3);
78 
79  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
80  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
81  QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString)));
82  QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString)));
83  QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int)));
84  QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int)));
85  QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(SetWidth(double)));
86  QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(SetHeight(double)));
87  QObject::connect(this,SIGNAL(VisibleChanged(bool)),this,SLOT(SetSubscription(bool)));
88  QObject::connect(ui_.keep_ratio, SIGNAL(toggled(bool)), this, SLOT(KeepRatioChanged(bool)));
89  QObject::connect(ui_.transport_combo_box, SIGNAL(activated(const QString&)),
90  this, SLOT(SetTransport(const QString&)));
91 
92  ui_.width->setKeyboardTracking(false);
93  ui_.height->setKeyboardTracking(false);
94  }
95 
97  {
98  }
99 
100  void ImagePlugin::SetOffsetX(int offset)
101  {
102  offset_x_ = offset;
103  }
104 
105  void ImagePlugin::SetOffsetY(int offset)
106  {
107  offset_y_ = offset;
108  }
109 
110  void ImagePlugin::SetWidth(double width)
111  {
112  width_ = width;
113  }
114 
115  void ImagePlugin::SetHeight(double height)
116  {
117  height_ = height;
118  }
119 
120  void ImagePlugin::SetAnchor(QString anchor)
121  {
122  if (anchor == "top left")
123  {
124  anchor_ = TOP_LEFT;
125  }
126  else if (anchor == "top center")
127  {
129  }
130  else if (anchor == "top right")
131  {
132  anchor_ = TOP_RIGHT;
133  }
134  else if (anchor == "center left")
135  {
137  }
138  else if (anchor == "center")
139  {
140  anchor_ = CENTER;
141  }
142  else if (anchor == "center right")
143  {
145  }
146  else if (anchor == "bottom left")
147  {
149  }
150  else if (anchor == "bottom center")
151  {
153  }
154  else if (anchor == "bottom right")
155  {
157  }
158  }
159 
160  void ImagePlugin::SetUnits(QString units)
161  {
162  // do this in both cases to avoid image clamping
163  ui_.width->setMaximum(10000);
164  ui_.height->setMaximum(10000);
165 
166  if (units == "pixels")
167  {
168  ui_.width->setDecimals(0);
169  ui_.height->setDecimals(0);
170  units_ = PIXELS;
171  width_ = width_ * double(canvas_->width()) / 100.0;
172  height_ = height_ * double(canvas_->height()) / 100.0;
173  ui_.width->setSuffix(" px");
174  ui_.height->setSuffix(" px");
175  }
176  else if (units == "percent")
177  {
178  ui_.width->setDecimals(1);
179  ui_.height->setDecimals(1);
180  units_ = PERCENT;
181  width_ = width_ * 100.0 / double(canvas_->width());
182  height_ = height_ * 100.0 / double(canvas_->height());
183  ui_.width->setSuffix(" %");
184  ui_.height->setSuffix(" %");
185  }
186  ui_.width->setValue( width_ );
187  ui_.height->setValue( height_ );
188 
189  if( units_ == PERCENT)
190  {
191  ui_.width->setMaximum(100);
192  ui_.height->setMaximum(100);
193  }
194 
195  }
196  void ImagePlugin::SetSubscription(bool visible)
197  {
198  if(topic_.empty())
199  {
200  return;
201  }
202  else if(!visible)
203  {
205  ROS_INFO("Dropped subscription to %s", topic_.c_str());
206  }
207  else
208  {
211 
212  ROS_INFO("Subscribing to %s", topic_.c_str());
213  }
214  }
215 
216  void ImagePlugin::SetTransport(const QString& transport)
217  {
218  ROS_INFO("Changing image_transport to %s.", transport.toStdString().c_str());
219  transport_ = transport;
220  TopicEdited();
221  }
222 
223  void ImagePlugin::KeepRatioChanged(bool checked)
224  {
225  ui_.height->setEnabled( !checked );
226  if( checked )
227  {
228  ui_.height->setValue( width_ * original_aspect_ratio_ );
229  }
230  }
231 
233  {
234  if (transport_ == QString::fromStdString("default"))
235  {
236  force_resubscribe_ = true;
237  TopicEdited();
238  }
239  }
240 
242  {
244  "sensor_msgs/Image");
245 
246  if(topic.name.empty())
247  {
248  topic.name.clear();
249  TopicEdited();
250 
251  }
252  if (!topic.name.empty())
253  {
254  ui_.topic->setText(QString::fromStdString(topic.name));
255  TopicEdited();
256  }
257  }
258 
260  {
261  std::string topic = ui_.topic->text().trimmed().toStdString();
262  if(!this->Visible())
263  {
264  PrintWarning("Topic is Hidden");
265  initialized_ = false;
266  has_message_ = false;
267  if (!topic.empty())
268  {
269  topic_ = topic;
270  }
272  return;
273  }
274  // Re-subscribe if either the topic or the image transport
275  // have changed.
276  if (force_resubscribe_ ||
277  topic != topic_ ||
278  image_sub_.getTransport() != transport_.toStdString())
279  {
280  force_resubscribe_ = false;
281  initialized_ = false;
282  has_message_ = false;
283  topic_ = topic;
284  PrintWarning("No messages received.");
285 
287 
288  if (!topic_.empty())
289  {
291  if (transport_ == QString::fromStdString("default"))
292  {
293  ROS_DEBUG("Using default transport.");
294  it = boost::make_shared<image_transport::ImageTransport>(node_);
295  image_sub_ = it->subscribe(topic_, 1, &ImagePlugin::imageCallback, this);
296  }
297  else
298  {
299  ROS_DEBUG("Setting transport to %s on %s.",
300  transport_.toStdString().c_str(), local_node_.getNamespace().c_str());
301 
302  local_node_.setParam("image_transport", transport_.toStdString());
303  it = boost::make_shared<image_transport::ImageTransport>(local_node_);
304  image_sub_ = it->subscribe(topic_, 1, &ImagePlugin::imageCallback, this,
307  local_node_));
308  }
309 
310  ROS_INFO("Subscribing to %s", topic_.c_str());
311  }
312  }
313  }
314 
315  void ImagePlugin::imageCallback(const sensor_msgs::ImageConstPtr& image)
316  {
317  if (!has_message_)
318  {
319  initialized_ = true;
320  has_message_ = true;
321  }
322 
323  image_ = *image;
324 
325  try
326  {
328  }
329  catch (const cv_bridge::Exception& e)
330  {
331  PrintError(e.what());
332  return;
333  }
334 
335  last_width_ = 0;
336  last_height_ = 0;
337  original_aspect_ratio_ = (double)image->height / (double)image->width;
338 
339  if( ui_.keep_ratio->isChecked() )
340  {
341  double height = width_ * original_aspect_ratio_;
342  if (units_ == PERCENT)
343  {
344  height *= (double)canvas_->width() / (double)canvas_->height();
345  }
346  ui_.height->setValue(height);
347  }
348 
349  has_image_ = true;
350  }
351 
352  void ImagePlugin::PrintError(const std::string& message)
353  {
354  PrintErrorHelper(ui_.status, message);
355  }
356 
357  void ImagePlugin::PrintInfo(const std::string& message)
358  {
359  PrintInfoHelper(ui_.status, message);
360  }
361 
362  void ImagePlugin::PrintWarning(const std::string& message)
363  {
364  PrintWarningHelper(ui_.status, message);
365  }
366 
367  QWidget* ImagePlugin::GetConfigWidget(QWidget* parent)
368  {
369  config_widget_->setParent(parent);
370 
371  return config_widget_;
372  }
373 
374  bool ImagePlugin::Initialize(QGLWidget* canvas)
375  {
376  canvas_ = canvas;
377 
378  return true;
379  }
380 
381  void ImagePlugin::ScaleImage(double width, double height)
382  {
383  if (!has_image_)
384  {
385  return;
386  }
387 
388  cv::resize(cv_image_->image, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA);
389  }
390 
391  void ImagePlugin::DrawIplImage(cv::Mat *image)
392  {
393  // TODO(malban) glTexture2D may be more efficient than glDrawPixels
394 
395  if (image == NULL || image->cols == 0 || image->rows == 0)
396  {
397  return;
398  }
399 
400  GLenum format;
401  switch (image->channels())
402  {
403  case 1:
404  format = GL_LUMINANCE;
405  break;
406  case 2:
407  format = GL_LUMINANCE_ALPHA;
408  break;
409  case 3:
410  format = GL_BGR;
411  break;
412  default:
413  return;
414  }
415 
416  glPixelZoom(1.0f, -1.0f);
417  glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
418  glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
419 
420  PrintInfo("OK");
421  }
422 
423  void ImagePlugin::Draw(double x, double y, double scale)
424  {
425  // Calculate the correct offsets and dimensions
426  double x_offset = offset_x_;
427  double y_offset = offset_y_;
428  double width = width_;
429  double height = height_;
430 
431  if (units_ == PERCENT)
432  {
433  x_offset = offset_x_ * canvas_->width() / 100.0;
434  y_offset = offset_y_ * canvas_->height() / 100.0;
435  width = width_ * canvas_->width() / 100.0;
436  height = height_ * canvas_->height() / 100.0;
437  }
438 
439  if( ui_.keep_ratio->isChecked() )
440  {
441  height = original_aspect_ratio_ * width;
442  }
443 
444  // Scale the source image if necessary
445  if (width != last_width_ || height != last_height_)
446  {
447  ScaleImage(width, height);
448  }
449 
450  // Calculate the correct render position
451  double x_pos = 0;
452  double y_pos = 0;
453  if (anchor_ == TOP_LEFT)
454  {
455  x_pos = x_offset;
456  y_pos = y_offset;
457  }
458  else if (anchor_ == TOP_CENTER)
459  {
460  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
461  y_pos = y_offset;
462  }
463  else if (anchor_ == TOP_RIGHT)
464  {
465  x_pos = canvas_->width() - width - x_offset;
466  y_pos = y_offset;
467  }
468  else if (anchor_ == CENTER_LEFT)
469  {
470  x_pos = x_offset;
471  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
472  }
473  else if (anchor_ == CENTER)
474  {
475  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
476  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
477  }
478  else if (anchor_ == CENTER_RIGHT)
479  {
480  x_pos = canvas_->width() - width - x_offset;
481  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
482  }
483  else if (anchor_ == BOTTOM_LEFT)
484  {
485  x_pos = x_offset;
486  y_pos = canvas_->height() - height - y_offset;
487  }
488  else if (anchor_ == BOTTOM_CENTER)
489  {
490  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
491  y_pos = canvas_->height() - height - y_offset;
492  }
493  else if (anchor_ == BOTTOM_RIGHT)
494  {
495  x_pos = canvas_->width() - width - x_offset;
496  y_pos = canvas_->height() - height - y_offset;
497  }
498 
499  glMatrixMode(GL_PROJECTION);
500  glPushMatrix();
501  glLoadIdentity();
502  glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f);
503 
504  glRasterPos2d(x_pos, y_pos);
505 
507 
508  glPopMatrix();
509 
510  last_width_ = width;
511  last_height_ = height;
512  }
513 
514  void ImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
515  {
516  // Note that image_transport should be loaded before the
517  // topic to make sure the transport is set appropriately before we
518  // subscribe.
519  if (node["image_transport"])
520  {
521  std::string transport;
522  node["image_transport"] >> transport;
523  transport_ = QString::fromStdString(transport);
524  int index = ui_.transport_combo_box->findText(transport_);
525  if (index != -1)
526  {
527  ui_.transport_combo_box->setCurrentIndex(index);
528  }
529  else
530  {
531  ROS_WARN("Saved image transport %s is unavailable.",
532  transport_.toStdString().c_str());
533  }
534  }
535 
536  if (node["topic"])
537  {
538  std::string topic;
539  node["topic"] >> topic;
540  ui_.topic->setText(topic.c_str());
541  TopicEdited();
542  }
543 
544  if (node["anchor"])
545  {
546  std::string anchor;
547  node["anchor"] >> anchor;
548  ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str()));
549  SetAnchor(anchor.c_str());
550  }
551 
552  if (node["units"])
553  {
554  std::string units;
555  node["units"] >> units;
556  ui_.units->setCurrentIndex(ui_.units->findText(units.c_str()));
557  SetUnits(units.c_str());
558  }
559 
560  if (node["offset_x"])
561  {
562  node["offset_x"] >> offset_x_;
563  ui_.offsetx->setValue(offset_x_);
564  }
565 
566  if (node["offset_y"])
567  {
568  node["offset_y"] >> offset_y_;
569  ui_.offsety->setValue(offset_y_);
570  }
571 
572  if (node["width"])
573  {
574  node["width"] >> width_;
575  ui_.width->setValue(width_);
576  }
577 
578  if (node["height"])
579  {
580  node["height"] >> height_;
581  ui_.height->setValue(height_);
582  }
583 
584  if (node["keep_ratio"])
585  {
586  bool keep;
587  node["keep_ratio"] >> keep;
588  ui_.keep_ratio->setChecked( keep );
589  }
590  }
591 
592  void ImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
593  {
594  emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
595  emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_);
596  emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_);
597  emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
598  emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
599  emitter << YAML::Key << "width" << YAML::Value << width_;
600  emitter << YAML::Key << "height" << YAML::Value << height_;
601  emitter << YAML::Key << "keep_ratio" << YAML::Value << ui_.keep_ratio->isChecked();
602  emitter << YAML::Key << "image_transport" << YAML::Value << transport_.toStdString();
603  }
604 
606  {
607  std::string anchor_string = "top left";
608 
609  if (anchor == TOP_LEFT)
610  {
611  anchor_string = "top left";
612  }
613  else if (anchor == TOP_CENTER)
614  {
615  anchor_string = "top center";
616  }
617  else if (anchor == TOP_RIGHT)
618  {
619  anchor_string = "top right";
620  }
621  else if (anchor == CENTER_LEFT)
622  {
623  anchor_string = "center left";
624  }
625  else if (anchor == CENTER)
626  {
627  anchor_string = "center";
628  }
629  else if (anchor == CENTER_RIGHT)
630  {
631  anchor_string = "center right";
632  }
633  else if (anchor == BOTTOM_LEFT)
634  {
635  anchor_string = "bottom left";
636  }
637  else if (anchor == BOTTOM_CENTER)
638  {
639  anchor_string = "bottom center";
640  }
641  else if (anchor == BOTTOM_RIGHT)
642  {
643  anchor_string = "bottom right";
644  }
645 
646  return anchor_string;
647  }
648 
650  {
651  std::string units_string = "pixels";
652 
653  if (units == PIXELS)
654  {
655  units_string = "pixels";
656  }
657  else if (units == PERCENT)
658  {
659  units_string = "percent";
660  }
661 
662  return units_string;
663  }
664 
666  {
667  // This is the same way ROS generates anonymous node names.
668  // See http://docs.ros.org/api/roscpp/html/this__node_8cpp_source.html
669  // Giving each image plugin a unique node means that we can control
670  // its image transport individually.
671  char buf[200];
672  snprintf(buf, sizeof(buf), "image_%llu", (unsigned long long)ros::WallTime::now().toNSec());
674  }
675 
677  {
678  node_ = node;
679 
680  // As soon as we have a node, we can find the available image transports
681  // and add them to our combo box.
683  std::vector<std::string> transports = it.getLoadableTransports();
684  Q_FOREACH (const std::string& transport, transports)
685  {
686  QString qtransport = QString::fromStdString(transport).replace("image_transport/", "");
687  ui_.transport_combo_box->addItem(qtransport);
688  }
689 
690  CreateLocalNode();
691  }
692 }
693 
void KeepRatioChanged(bool checked)
void PrintInfo(const std::string &message)
std::vector< std::string > getLoadableTransports() const
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())
#define NULL
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
ros::NodeHandle local_node_
Definition: image_plugin.h:138
void DrawIplImage(cv::Mat *image)
bool Initialize(QGLWidget *canvas)
bool Visible() const
ros::NodeHandle node_
virtual void SetNode(const ros::NodeHandle &node)
f
sensor_msgs::Image image_
Definition: image_plugin.h:142
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
void SetWidth(double width)
#define ROS_WARN(...)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void ScaleImage(double width, double height)
void SetAnchor(QString anchor)
image_transport::Subscriber image_sub_
Definition: image_plugin.h:139
std::string getTransport() const
void SetUnits(QString units)
#define ROS_INFO(...)
void LoadConfig(const YAML::Node &node, const std::string &path)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string & getNamespace() const
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void SetSubscription(bool visible)
std::string AnchorToString(Anchor anchor)
void SetTransport(const QString &transport)
void VisibleChanged(bool visible)
void PrintWarning(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
static WallTime now()
cv_bridge::CvImagePtr cv_image_
Definition: image_plugin.h:144
std::string UnitsToString(Units units)
void SetHeight(double height)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void imageCallback(const sensor_msgs::ImageConstPtr &image)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void Draw(double x, double y, double scale)
#define ROS_DEBUG(...)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 19:25:16