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 {
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  rotation_(-1),
63  has_image_(false),
64  last_width_(0),
65  last_height_(0),
66  original_aspect_ratio_(1.0)
67  {
68  ui_.setupUi(config_widget_);
69 
70  // Set background white
71  QPalette p(config_widget_->palette());
72  p.setColor(QPalette::Background, Qt::white);
73  config_widget_->setPalette(p);
74 
75  // Set status text red
76  QPalette p3(ui_.status->palette());
77  p3.setColor(QPalette::Text, Qt::red);
78  ui_.status->setPalette(p3);
79 
80  QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
81  QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
82  QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString)));
83  QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString)));
84  QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int)));
85  QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int)));
86  QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(SetWidth(double)));
87  QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(SetHeight(double)));
88  QObject::connect(this,SIGNAL(VisibleChanged(bool)),this,SLOT(SetSubscription(bool)));
89  QObject::connect(ui_.keep_ratio, SIGNAL(toggled(bool)), this, SLOT(KeepRatioChanged(bool)));
90  QObject::connect(ui_.transport_combo_box, SIGNAL(activated(const QString&)),
91  this, SLOT(SetTransport(const QString&)));
92  QObject::connect(ui_.rotation, SIGNAL(activated(QString)), this, SLOT(SetRotation(QString)));
93 
94  ui_.width->setKeyboardTracking(false);
95  ui_.height->setKeyboardTracking(false);
96  }
97 
99  {
100  }
101 
102  void ImagePlugin::SetOffsetX(int offset)
103  {
104  offset_x_ = offset;
105  }
106 
107  void ImagePlugin::SetOffsetY(int offset)
108  {
109  offset_y_ = offset;
110  }
111 
112  void ImagePlugin::SetWidth(double width)
113  {
114  width_ = width;
115  }
116 
117  void ImagePlugin::SetHeight(double height)
118  {
119  height_ = height;
120  }
121 
122  void ImagePlugin::SetAnchor(QString anchor)
123  {
124  if (anchor == "top left")
125  {
126  anchor_ = TOP_LEFT;
127  }
128  else if (anchor == "top center")
129  {
131  }
132  else if (anchor == "top right")
133  {
134  anchor_ = TOP_RIGHT;
135  }
136  else if (anchor == "center left")
137  {
139  }
140  else if (anchor == "center")
141  {
142  anchor_ = CENTER;
143  }
144  else if (anchor == "center right")
145  {
147  }
148  else if (anchor == "bottom left")
149  {
151  }
152  else if (anchor == "bottom center")
153  {
155  }
156  else if (anchor == "bottom right")
157  {
159  }
160  }
161 
162  void ImagePlugin::SetUnits(QString units)
163  {
164  // do this in both cases to avoid image clamping
165  ui_.width->setMaximum(10000);
166  ui_.height->setMaximum(10000);
167 
168  if (units == "pixels")
169  {
170  ui_.width->setDecimals(0);
171  ui_.height->setDecimals(0);
172  units_ = PIXELS;
173  width_ = width_ * double(canvas_->width()) / 100.0;
174  height_ = height_ * double(canvas_->height()) / 100.0;
175  ui_.width->setSuffix(" px");
176  ui_.height->setSuffix(" px");
177  }
178  else if (units == "percent")
179  {
180  ui_.width->setDecimals(1);
181  ui_.height->setDecimals(1);
182  units_ = PERCENT;
183  width_ = width_ * 100.0 / double(canvas_->width());
184  height_ = height_ * 100.0 / double(canvas_->height());
185  ui_.width->setSuffix(" %");
186  ui_.height->setSuffix(" %");
187  }
188  ui_.width->setValue( width_ );
189  ui_.height->setValue( height_ );
190 
191  if( units_ == PERCENT)
192  {
193  ui_.width->setMaximum(100);
194  ui_.height->setMaximum(100);
195  }
196 
197  }
198  void ImagePlugin::SetSubscription(bool visible)
199  {
200  if(topic_.empty())
201  {
202  return;
203  }
204  else if(!visible)
205  {
207  ROS_INFO("Dropped subscription to %s", topic_.c_str());
208  }
209  else
210  {
211  Resubscribe();
212  }
213  }
214 
215  void ImagePlugin::SetTransport(const QString& transport)
216  {
217  transport_ = transport.toStdString();
218  ROS_INFO("Changing image_transport to %s.", transport_.c_str());
219  TopicEdited();
220  }
221 
222  void ImagePlugin::SetRotation(QString rotation)
223  {
224 
225  if ((rotation == "90°") || (rotation == "90"))
226  {
227  rotation_ = cv::ROTATE_90_CLOCKWISE;
228  }
229  else if ((rotation == "180°") || (rotation == "180"))
230  {
231  rotation_ = cv::ROTATE_180;
232  }
233  else if ((rotation == "270°") || (rotation == "270"))
234  {
235  rotation_ = cv::ROTATE_90_COUNTERCLOCKWISE;
236  }
237  else {
238  rotation_ = -1;
239  }
240  }
241 
242  void ImagePlugin::KeepRatioChanged(bool checked)
243  {
244  ui_.height->setEnabled( !checked );
245  if( checked )
246  {
247  ui_.height->setValue( width_ * original_aspect_ratio_ );
248  }
249  }
250 
252  {
253  if (transport_ == "default")
254  {
255  force_resubscribe_ = true;
256  TopicEdited();
257  }
258  }
259 
261  {
263  "sensor_msgs/Image");
264 
265  if(topic.name.empty())
266  {
267  topic.name.clear();
268  TopicEdited();
269 
270  }
271  if (!topic.name.empty())
272  {
273  ui_.topic->setText(QString::fromStdString(topic.name));
274  TopicEdited();
275  }
276  }
277 
279  {
280  std::string topic = ui_.topic->text().trimmed().toStdString();
281  if(!this->Visible())
282  {
283  PrintWarning("Topic is Hidden");
284  initialized_ = false;
285  has_message_ = false;
286  if (!topic.empty())
287  {
288  topic_ = topic;
289  }
291  return;
292  }
293  // Re-subscribe if either the topic or the image transport
294  // have changed.
295  if (force_resubscribe_ ||
296  topic != topic_ ||
298  {
299  force_resubscribe_ = false;
300  initialized_ = false;
301  has_message_ = false;
302  topic_ = topic;
303  PrintWarning("No messages received.");
304 
306 
307  if (!topic_.empty())
308  {
310  if (transport_ == "default")
311  {
312  ROS_DEBUG("Using default transport.");
315  }
316  else
317  {
318  ROS_DEBUG("Setting transport to %s on %s.",
319  transport_.c_str(), local_node_.getNamespace().c_str());
320 
321  local_node_.setParam("image_transport", transport_);
326  local_node_));
327  }
328 
329  ROS_INFO("Subscribing to %s", topic_.c_str());
330  }
331  }
332  }
333 
334  void ImagePlugin::imageCallback(const sensor_msgs::ImageConstPtr& image)
335  {
336  if (!has_message_)
337  {
338  initialized_ = true;
339  has_message_ = true;
340  }
341 
342  image_ = *image;
343 
344  try
345  {
347  }
348  catch (const cv_bridge::Exception& e)
349  {
350  PrintError(e.what());
351  return;
352  }
353 
354  last_width_ = 0;
355  last_height_ = 0;
356  original_aspect_ratio_ = (double)image->height / (double)image->width;
357 
358  if( ui_.keep_ratio->isChecked() )
359  {
360  double height = width_ * original_aspect_ratio_;
361  if (units_ == PERCENT)
362  {
363  height *= (double)canvas_->width() / (double)canvas_->height();
364  }
365  ui_.height->setValue(height);
366  }
367 
368  has_image_ = true;
369  }
370 
371  void ImagePlugin::PrintError(const std::string& message)
372  {
373  PrintErrorHelper(ui_.status, message);
374  }
375 
376  void ImagePlugin::PrintInfo(const std::string& message)
377  {
378  PrintInfoHelper(ui_.status, message);
379  }
380 
381  void ImagePlugin::PrintWarning(const std::string& message)
382  {
383  PrintWarningHelper(ui_.status, message);
384  }
385 
386  QWidget* ImagePlugin::GetConfigWidget(QWidget* parent)
387  {
388  config_widget_->setParent(parent);
389 
390  return config_widget_;
391  }
392 
393  bool ImagePlugin::Initialize(QGLWidget* canvas)
394  {
395  canvas_ = canvas;
396 
397  return true;
398  }
399 
400  void ImagePlugin::ScaleImage(double width, double height)
401  {
402  if (!has_image_)
403  {
404  return;
405  }
406 
407  cv::resize(cv_image_->image, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA);
408  }
409 
410  void ImagePlugin::DrawIplImage(cv::Mat *image)
411  {
412  // TODO(malban) glTexture2D may be more efficient than glDrawPixels
413 
414  if (image == NULL || image->cols == 0 || image->rows == 0)
415  {
416  return;
417  }
418 
419  GLenum format;
420  switch (image->channels())
421  {
422  case 1:
423  format = GL_LUMINANCE;
424  break;
425  case 2:
426  format = GL_LUMINANCE_ALPHA;
427  break;
428  case 3:
429  format = GL_BGR;
430  break;
431  default:
432  return;
433  }
434 
435  glPixelZoom(1.0f, -1.0f);
436  glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
437  glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
438  glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
439 
440 
441  PrintInfo("OK");
442  }
443 
444  void ImagePlugin::Draw(double x, double y, double scale)
445  {
446  // Calculate the correct offsets and dimensions
447  double x_offset = offset_x_;
448  double y_offset = offset_y_;
449  double width = width_;
450  double height = height_;
451 
452  if (units_ == PERCENT)
453  {
454  x_offset = offset_x_ * canvas_->width() / 100.0;
455  y_offset = offset_y_ * canvas_->height() / 100.0;
456  width = width_ * canvas_->width() / 100.0;
457  height = height_ * canvas_->height() / 100.0;
458  }
459 
460  if( ui_.keep_ratio->isChecked() )
461  {
462  height = original_aspect_ratio_ * width;
463  }
464 
465  // Scale the source image if necessary
466  if (width != last_width_ || height != last_height_)
467  {
468  ScaleImage(width, height);
469  }
470 
471  // Rotate the source image if necessary
472  if(rotation_ >= cv::ROTATE_90_CLOCKWISE && rotation_ <= cv::ROTATE_90_COUNTERCLOCKWISE){
473  cv::rotate(scaled_image_, rotated_image_, rotation_);
474  //-- If we did not rotate 180, we have flipped width / height
475  if(rotation_ != cv::ROTATE_180){
476  height = width_;
477  width = height_;
478  }
479  }
480  else{
482  }
483 
484  // Calculate the correct render position
485  double x_pos = 0;
486  double y_pos = 0;
487  if (anchor_ == TOP_LEFT)
488  {
489  x_pos = x_offset;
490  y_pos = y_offset;
491  }
492  else if (anchor_ == TOP_CENTER)
493  {
494  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
495  y_pos = y_offset;
496  }
497  else if (anchor_ == TOP_RIGHT)
498  {
499  x_pos = canvas_->width() - width - x_offset;
500  y_pos = y_offset;
501  }
502  else if (anchor_ == CENTER_LEFT)
503  {
504  x_pos = x_offset;
505  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
506  }
507  else if (anchor_ == CENTER)
508  {
509  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
510  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
511  }
512  else if (anchor_ == CENTER_RIGHT)
513  {
514  x_pos = canvas_->width() - width - x_offset;
515  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
516  }
517  else if (anchor_ == BOTTOM_LEFT)
518  {
519  x_pos = x_offset;
520  y_pos = canvas_->height() - height - y_offset;
521  }
522  else if (anchor_ == BOTTOM_CENTER)
523  {
524  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
525  y_pos = canvas_->height() - height - y_offset;
526  }
527  else if (anchor_ == BOTTOM_RIGHT)
528  {
529  x_pos = canvas_->width() - width - x_offset;
530  y_pos = canvas_->height() - height - y_offset;
531  }
532 
533  glMatrixMode(GL_PROJECTION);
534  glPushMatrix();
535  glLoadIdentity();
536  glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f);
537 
538  glRasterPos2d(x_pos, y_pos);
539 
541 
542  glPopMatrix();
543 
544  last_width_ = width;
545  last_height_ = height;
546  }
547 
548  void ImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path)
549  {
550  // Note that image_transport should be loaded before the
551  // topic to make sure the transport is set appropriately before we
552  // subscribe.
553  if (node["image_transport"])
554  {
555  node["image_transport"] >> transport_;
556  int index = ui_.transport_combo_box->findText( QString::fromStdString(transport_) );
557  if (index != -1)
558  {
559  ui_.transport_combo_box->setCurrentIndex(index);
560  }
561  else
562  {
563  ROS_WARN("Saved image transport %s is unavailable.",
564  transport_.c_str());
565  }
566  }
567 
568  if (node["topic"])
569  {
570  std::string topic;
571  node["topic"] >> topic;
572  ui_.topic->setText(topic.c_str());
573  TopicEdited();
574  }
575 
576  if (node["anchor"])
577  {
578  std::string anchor;
579  node["anchor"] >> anchor;
580  ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str()));
581  SetAnchor(anchor.c_str());
582  }
583 
584  if (node["rotation"])
585  {
586  std::string rotation;
587  node["rotation"] >> rotation;
588  ui_.rotation->setCurrentIndex(ui_.rotation->findText(rotation.c_str()));
589  SetRotation(rotation.c_str());
590  }
591 
592  if (node["units"])
593  {
594  std::string units;
595  node["units"] >> units;
596  ui_.units->setCurrentIndex(ui_.units->findText(units.c_str()));
597  SetUnits(units.c_str());
598  }
599 
600  if (node["offset_x"])
601  {
602  node["offset_x"] >> offset_x_;
603  ui_.offsetx->setValue(offset_x_);
604  }
605 
606  if (node["offset_y"])
607  {
608  node["offset_y"] >> offset_y_;
609  ui_.offsety->setValue(offset_y_);
610  }
611 
612  if (node["width"])
613  {
614  node["width"] >> width_;
615  ui_.width->setValue(width_);
616  }
617 
618  if (node["height"])
619  {
620  node["height"] >> height_;
621  ui_.height->setValue(height_);
622  }
623 
624  if (node["keep_ratio"])
625  {
626  bool keep;
627  node["keep_ratio"] >> keep;
628  ui_.keep_ratio->setChecked( keep );
629  }
630  }
631 
632  void ImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
633  {
634  emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
635  emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_);
636  emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_);
637  emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
638  emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
639  emitter << YAML::Key << "width" << YAML::Value << width_;
640  emitter << YAML::Key << "height" << YAML::Value << height_;
641  emitter << YAML::Key << "keep_ratio" << YAML::Value << ui_.keep_ratio->isChecked();
642  emitter << YAML::Key << "image_transport" << YAML::Value << transport_;
643  emitter << YAML::Key << "rotation" << YAML::Value << RotationToString(rotation_);
644  }
645 
647  {
648  std::string anchor_string = "top left";
649 
650  if (anchor == TOP_LEFT)
651  {
652  anchor_string = "top left";
653  }
654  else if (anchor == TOP_CENTER)
655  {
656  anchor_string = "top center";
657  }
658  else if (anchor == TOP_RIGHT)
659  {
660  anchor_string = "top right";
661  }
662  else if (anchor == CENTER_LEFT)
663  {
664  anchor_string = "center left";
665  }
666  else if (anchor == CENTER)
667  {
668  anchor_string = "center";
669  }
670  else if (anchor == CENTER_RIGHT)
671  {
672  anchor_string = "center right";
673  }
674  else if (anchor == BOTTOM_LEFT)
675  {
676  anchor_string = "bottom left";
677  }
678  else if (anchor == BOTTOM_CENTER)
679  {
680  anchor_string = "bottom center";
681  }
682  else if (anchor == BOTTOM_RIGHT)
683  {
684  anchor_string = "bottom right";
685  }
686 
687  return anchor_string;
688  }
689 
691  {
692  std::string units_string = "pixels";
693 
694  if (units == PIXELS)
695  {
696  units_string = "pixels";
697  }
698  else if (units == PERCENT)
699  {
700  units_string = "percent";
701  }
702 
703  return units_string;
704  }
705 
706  std::string ImagePlugin::RotationToString(int rotation)
707  {
708  std::string rotation_string = "0°";
709 
710  if (rotation == cv::ROTATE_90_CLOCKWISE) { rotation_string = "90°"; }
711  else if (rotation == cv::ROTATE_180) { rotation_string = "180°"; }
712  else if (rotation == cv::ROTATE_90_COUNTERCLOCKWISE) { rotation_string = "270°"; }
713 
714  return rotation_string;
715  }
716 
718  {
719  // This is the same way ROS generates anonymous node names.
720  // See http://docs.ros.org/api/roscpp/html/this__node_8cpp_source.html
721  // Giving each image plugin a unique node means that we can control
722  // its image transport individually.
723  char buf[200];
724  snprintf(buf, sizeof(buf), "image_%llu", (unsigned long long)ros::WallTime::now().toNSec());
726  }
727 
729  {
730  node_ = node;
731 
732  // As soon as we have a node, we can find the available image transports
733  // and add them to our combo box.
735  std::vector<std::string> transports = it.getLoadableTransports();
736  Q_FOREACH (const std::string& transport, transports)
737  {
738  QString qtransport = QString::fromStdString(transport).replace("image_transport/", "");
739  ui_.transport_combo_box->addItem(qtransport);
740  }
741 
742  CreateLocalNode();
743  }
744 }
745 
mapviz_plugins::ImagePlugin::DrawIplImage
void DrawIplImage(cv::Mat *image)
Definition: image_plugin.cpp:410
mapviz_plugins::ImagePlugin::SetNode
virtual void SetNode(const ros::NodeHandle &node)
Definition: image_plugin.cpp:728
mapviz_plugins::ImagePlugin::BOTTOM_RIGHT
@ BOTTOM_RIGHT
Definition: image_plugin.h:74
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
mapviz_plugins::ImagePlugin::SetOffsetX
void SetOffsetX(int offset)
Definition: image_plugin.cpp:102
select_topic_dialog.h
NULL
#define NULL
mapviz_plugins::ImagePlugin::SetOffsetY
void SetOffsetY(int offset)
Definition: image_plugin.cpp:107
image_encodings.h
mapviz_plugins::ImagePlugin::units_
Units units_
Definition: image_plugin.h:125
mapviz_plugins::ImagePlugin::Resubscribe
void Resubscribe()
Definition: image_plugin.cpp:251
mapviz_plugins::ImagePlugin::SetTransport
void SetTransport(const QString &transport)
Definition: image_plugin.cpp:215
image_transport::ImageTransport
mapviz_plugins::ImagePlugin
Definition: image_plugin.h:60
mapviz_plugins::ImagePlugin::rotation_
int rotation_
Definition: image_plugin.h:131
boost::shared_ptr
mapviz_plugins::ImagePlugin::CreateLocalNode
void CreateLocalNode()
Definition: image_plugin.cpp:717
mapviz_plugins::ImagePlugin::BOTTOM_CENTER
@ BOTTOM_CENTER
Definition: image_plugin.h:73
mapviz_plugins::ImagePlugin::has_message_
bool has_message_
Definition: image_plugin.h:143
mapviz::MapvizPlugin::PrintErrorHelper
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::ImagePlugin::last_height_
double last_height_
Definition: image_plugin.h:137
mapviz_plugins::ImagePlugin::config_widget_
QWidget * config_widget_
Definition: image_plugin.h:121
mapviz_plugins::ImagePlugin::TOP_RIGHT
@ TOP_RIGHT
Definition: image_plugin.h:68
mapviz_plugins::ImagePlugin::topic_
std::string topic_
Definition: image_plugin.h:123
mapviz_plugins::ImagePlugin::ImagePlugin
ImagePlugin()
Definition: image_plugin.cpp:53
ros::TransportHints
image_transport::Subscriber::getTransport
std::string getTransport() const
mapviz_plugins::ImagePlugin::scaled_image_
cv::Mat scaled_image_
Definition: image_plugin.h:148
mapviz_plugins::ImagePlugin::Anchor
Anchor
Definition: image_plugin.h:65
mapviz_plugins::ImagePlugin::CENTER
@ CENTER
Definition: image_plugin.h:70
mapviz_plugins::ImagePlugin::image_sub_
image_transport::Subscriber image_sub_
Definition: image_plugin.h:142
cv_bridge::Exception
mapviz_plugins::ImagePlugin::BOTTOM_LEFT
@ BOTTOM_LEFT
Definition: image_plugin.h:72
mapviz_plugins::ImagePlugin::PrintError
void PrintError(const std::string &message)
Definition: image_plugin.cpp:371
mapviz_plugins::ImagePlugin::last_width_
double last_width_
Definition: image_plugin.h:136
f
f
mapviz_plugins::ImagePlugin::Draw
void Draw(double x, double y, double scale)
Definition: image_plugin.cpp:444
mapviz_plugins::ImagePlugin::TOP_LEFT
@ TOP_LEFT
Definition: image_plugin.h:66
mapviz_plugins::ImagePlugin::UnitsToString
std::string UnitsToString(Units units)
Definition: image_plugin.cpp:690
mapviz_plugins::ImagePlugin::original_aspect_ratio_
double original_aspect_ratio_
Definition: image_plugin.h:139
mapviz_plugins::ImagePlugin::height_
double height_
Definition: image_plugin.h:129
class_list_macros.h
mapviz_plugins::ImagePlugin::TOP_CENTER
@ TOP_CENTER
Definition: image_plugin.h:67
mapviz_plugins::ImagePlugin::LoadConfig
void LoadConfig(const YAML::Node &node, const std::string &path)
Definition: image_plugin.cpp:548
mapviz_plugins::ImagePlugin::SelectTopic
void SelectTopic()
Definition: image_plugin.cpp:260
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mapviz_plugins::ImagePlugin::local_node_
ros::NodeHandle local_node_
Definition: image_plugin.h:141
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
ROS_DEBUG
#define ROS_DEBUG(...)
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())
ros::WallTime::now
static WallTime now()
mapviz_plugins::ImagePlugin::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &image)
Definition: image_plugin.cpp:334
mapviz_plugins::ImagePlugin::SetUnits
void SetUnits(QString units)
Definition: image_plugin.cpp:162
mapviz_plugins::ImagePlugin::rotated_image_
cv::Mat rotated_image_
Definition: image_plugin.h:149
mapviz::MapvizPlugin::PrintWarningHelper
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
ROS_WARN
#define ROS_WARN(...)
mapviz_plugins::ImagePlugin::has_image_
bool has_image_
Definition: image_plugin.h:134
mapviz_plugins::ImagePlugin::RotationToString
std::string RotationToString(int rotation)
Definition: image_plugin.cpp:706
mapviz_plugins::ImagePlugin::SetRotation
void SetRotation(QString rotation)
Definition: image_plugin.cpp:222
mapviz_plugins::ImagePlugin::TopicEdited
void TopicEdited()
Definition: image_plugin.cpp:278
mapviz::MapvizPlugin::PrintInfoHelper
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
mapviz_plugins::ImagePlugin::AnchorToString
std::string AnchorToString(Anchor anchor)
Definition: image_plugin.cpp:646
mapviz_plugins::ImagePlugin::KeepRatioChanged
void KeepRatioChanged(bool checked)
Definition: image_plugin.cpp:242
mapviz::MapvizPlugin::canvas_
QGLWidget * canvas_
mapviz_plugins::ImagePlugin::SetHeight
void SetHeight(double height)
Definition: image_plugin.cpp:117
mapviz::MapvizPlugin::VisibleChanged
void VisibleChanged(bool visible)
mapviz_plugins::ImagePlugin::CENTER_RIGHT
@ CENTER_RIGHT
Definition: image_plugin.h:71
mapviz_plugins::ImagePlugin::PERCENT
@ PERCENT
Definition: image_plugin.h:77
mapviz_plugins::ImagePlugin::offset_x_
int offset_x_
Definition: image_plugin.h:126
mapviz_plugins::ImagePlugin::~ImagePlugin
virtual ~ImagePlugin()
Definition: image_plugin.cpp:98
mapviz_plugins::ImagePlugin::SetAnchor
void SetAnchor(QString anchor)
Definition: image_plugin.cpp:122
mapviz_plugins::ImagePlugin::ScaleImage
void ScaleImage(double width, double height)
Definition: image_plugin.cpp:400
mapviz::MapvizPlugin
mapviz_plugins::ImagePlugin::width_
double width_
Definition: image_plugin.h:128
mapviz::MapvizPlugin::Visible
bool Visible() const
sensor_msgs::image_encodings::BGR8
const std::string BGR8
mapviz::MapvizPlugin::initialized_
bool initialized_
mapviz_plugins::ImagePlugin::anchor_
Anchor anchor_
Definition: image_plugin.h:124
mapviz_plugins::ImagePlugin::SaveConfig
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
Definition: image_plugin.cpp:632
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
image_transport::TransportHints
image_transport::ImageTransport::getLoadableTransports
std::vector< std::string > getLoadableTransports() const
mapviz_plugins::ImagePlugin::transport_
std::string transport_
Definition: image_plugin.h:130
mapviz_plugins::ImagePlugin::Units
Units
Definition: image_plugin.h:77
image_plugin.h
ROS_INFO
#define ROS_INFO(...)
ros::master::TopicInfo
mapviz_plugins::ImagePlugin::cv_image_
cv_bridge::CvImagePtr cv_image_
Definition: image_plugin.h:147
mapviz_plugins
Definition: attitude_indicator_plugin.h:61
master.h
mapviz::MapvizPlugin::node_
ros::NodeHandle node_
mapviz_plugins::ImagePlugin::SetSubscription
void SetSubscription(bool visible)
Definition: image_plugin.cpp:198
mapviz_plugins::ImagePlugin::SetWidth
void SetWidth(double width)
Definition: image_plugin.cpp:112
mapviz_plugins::ImagePlugin::offset_y_
int offset_y_
Definition: image_plugin.h:127
mapviz_plugins::ImagePlugin::GetConfigWidget
QWidget * GetConfigWidget(QWidget *parent)
Definition: image_plugin.cpp:386
mapviz_plugins::ImagePlugin::PrintInfo
void PrintInfo(const std::string &message)
Definition: image_plugin.cpp:376
mapviz_plugins::ImagePlugin::force_resubscribe_
bool force_resubscribe_
Definition: image_plugin.h:133
mapviz_plugins::ImagePlugin::CENTER_LEFT
@ CENTER_LEFT
Definition: image_plugin.h:69
mapviz_plugins::ImagePlugin::ui_
Ui::image_config ui_
Definition: image_plugin.h:120
mapviz::SelectTopicDialog::selectTopic
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
mapviz_plugins::ImagePlugin::PIXELS
@ PIXELS
Definition: image_plugin.h:77
ros::NodeHandle
mapviz_plugins::ImagePlugin::PrintWarning
void PrintWarning(const std::string &message)
Definition: image_plugin.cpp:381
ros::master::TopicInfo::name
std::string name
mapviz_plugins::ImagePlugin::image_
sensor_msgs::Image image_
Definition: image_plugin.h:145
mapviz_plugins::ImagePlugin::Initialize
bool Initialize(QGLWidget *canvas)
Definition: image_plugin.cpp:393
image_transport::Subscriber::shutdown
void shutdown()


mapviz_plugins
Author(s): Marc Alban
autogenerated on Sun Sep 8 2024 02:27:14