disparity_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 <algorithm>
35 #include <vector>
36 
37 // QT libraries
38 #include <QDialog>
39 #include <QGLWidget>
40 
41 // ROS libraries
42 #include <ros/master.h>
44 #include <opencv2/imgproc/imgproc.hpp>
45 
46 #include <cv_bridge/cv_bridge.h>
47 
49 
50 // Declare plugin
53 
54 namespace mapviz_plugins
55 {
56  DisparityPlugin::DisparityPlugin() :
57  config_widget_(new QWidget()),
58  anchor_(TOP_LEFT),
59  units_(PIXELS),
60  offset_x_(0),
61  offset_y_(0),
62  width_(320),
63  height_(240),
64  has_image_(false),
65  last_width_(0),
66  last_height_(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(int)), this, SLOT(SetWidth(int)));
87  QObject::connect(ui_.height, SIGNAL(valueChanged(int)), this, SLOT(SetHeight(int)));
88  QObject::connect(this,SIGNAL(VisibleChanged(bool)),this,SLOT(SetSubscription(bool)));
89  }
90 
92  {
93  }
94 
95  void DisparityPlugin::SetOffsetX(int offset)
96  {
97  offset_x_ = offset;
98  }
99 
101  {
102  offset_y_ = offset;
103  }
104 
106  {
107  width_ = width;
108  }
109 
110  void DisparityPlugin::SetHeight(int height)
111  {
112  height_ = height;
113  }
114 
115  void DisparityPlugin::SetAnchor(QString anchor)
116  {
117  if (anchor == "top left")
118  {
119  anchor_ = TOP_LEFT;
120  }
121  else if (anchor == "top center")
122  {
124  }
125  else if (anchor == "top right")
126  {
127  anchor_ = TOP_RIGHT;
128  }
129  else if (anchor == "center left")
130  {
132  }
133  else if (anchor == "center")
134  {
135  anchor_ = CENTER;
136  }
137  else if (anchor == "center right")
138  {
140  }
141  else if (anchor == "bottom left")
142  {
144  }
145  else if (anchor == "bottom center")
146  {
148  }
149  else if (anchor == "bottom right")
150  {
152  }
153  }
154 
155  void DisparityPlugin::SetUnits(QString units)
156  {
157  if (units == "pixels")
158  {
159  units_ = PIXELS;
160  }
161  else if (units == "percent")
162  {
163  units_ = PERCENT;
164  }
165  }
167  {
168  if(topic_.empty())
169  {
170  return;
171  }
172  else if(!visible)
173  {
175  ROS_INFO("Dropped subscription to %s", topic_.c_str());
176  }
177  else
178  {
180 
181  ROS_INFO("Subscribing to %s", topic_.c_str());
182  }
183  }
185  {
187  "stereo_msgs/DisparityImage");
188 
189  if(topic.name.empty())
190  {
191  topic.name.clear();
192  }
193  if (!topic.name.empty())
194  {
195  ui_.topic->setText(QString::fromStdString(topic.name));
196  }
197  TopicEdited();
198  }
199 
201  {
202  std::string topic = ui_.topic->text().trimmed().toStdString();
203  if(!this->Visible())
204  {
205  PrintWarning("Topic is Hidden");
206  initialized_ = false;
207  has_message_ = false;
208  if (!topic.empty())
209  {
210  topic_ = topic;
211  }
213  return;
214  }
215  if (topic != topic_)
216  {
217  PrintWarning("Topic is Hidden");
218  initialized_ = false;
219  has_message_ = false;
220  topic_ = topic;
221  PrintWarning("No messages received.");
222 
224 
225  if (!topic.empty())
226  {
228 
229  ROS_INFO("Subscribing to %s", topic_.c_str());
230  }
231  }
232  }
233 
234  void DisparityPlugin::disparityCallback(const stereo_msgs::DisparityImageConstPtr& disparity)
235  {
236  if (!has_message_)
237  {
238  initialized_ = true;
239  has_message_ = true;
240  }
241 
242  if (disparity->min_disparity == 0.0 && disparity->max_disparity == 0.0)
243  {
244  PrintError("Min and max disparity not set.");
245  has_image_ = false;
246  return;
247  }
248 
249  if (disparity->image.encoding != sensor_msgs::image_encodings::TYPE_32FC1)
250  {
251  PrintError("Invalid encoding.");
252  has_image_ = false;
253  return;
254  }
255 
256  disparity_ = *disparity;
257 
258  // Colormap and display the disparity image
259  float min_disparity = disparity->min_disparity;
260  float max_disparity = disparity->max_disparity;
261  float multiplier = 255.0f / (max_disparity - min_disparity);
262 
263  cv_bridge::CvImageConstPtr cv_disparity =
264  cv_bridge::toCvShare(disparity->image, disparity);
265 
266  disparity_color_.create(disparity->image.height, disparity->image.width);
267 
268  for (int row = 0; row < disparity_color_.rows; row++)
269  {
270  const float* d = cv_disparity->image.ptr<float>(row);
271  for (int col = 0; col < disparity_color_.cols; col++)
272  {
273  int index = static_cast<int>((d[col] - min_disparity) * multiplier + 0.5);
274  index = std::min(255, std::max(0, index));
275  // Fill as BGR
276  disparity_color_(row, col)[2] = COLOR_MAP[3*index + 0];
277  disparity_color_(row, col)[1] = COLOR_MAP[3*index + 1];
278  disparity_color_(row, col)[0] = COLOR_MAP[3*index + 2];
279  }
280  }
281 
282  last_width_ = 0;
283  last_height_ = 0;
284 
285  has_image_ = true;
286  }
287 
288  void DisparityPlugin::PrintError(const std::string& message)
289  {
290  PrintErrorHelper(ui_.status, message);
291  }
292 
293  void DisparityPlugin::PrintInfo(const std::string& message)
294  {
295  PrintInfoHelper(ui_.status, message);
296  }
297 
298  void DisparityPlugin::PrintWarning(const std::string& message)
299  {
300  PrintWarningHelper(ui_.status, message);
301  }
302 
303  QWidget* DisparityPlugin::GetConfigWidget(QWidget* parent)
304  {
305  config_widget_->setParent(parent);
306 
307  return config_widget_;
308  }
309 
310  bool DisparityPlugin::Initialize(QGLWidget* canvas)
311  {
312  canvas_ = canvas;
313 
314  return true;
315  }
316 
317  void DisparityPlugin::ScaleImage(double width, double height)
318  {
319  if (!has_image_)
320  {
321  return;
322  }
323 
324  cv::resize(disparity_color_, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA);
325  }
326 
327  void DisparityPlugin::DrawIplImage(cv::Mat *image)
328  {
329  // TODO(malban): glTexture2D may be more efficient than glDrawPixels
330 
331  if (!has_image_)
332  return;
333 
334  if (image == NULL)
335  return;
336 
337  if (image->cols == 0 || image->rows == 0)
338  return;
339 
340  GLenum format;
341  switch (image->channels())
342  {
343  case 1:
344  format = GL_LUMINANCE;
345  break;
346  case 2:
347  format = GL_LUMINANCE_ALPHA;
348  break;
349  case 3:
350  format = GL_BGR;
351  break;
352  default:
353  return;
354  }
355 
356  glPixelZoom(1.0, -1.0f);
357  glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr());
358 
359  PrintInfo("OK");
360  }
361 
362  void DisparityPlugin::Draw(double x, double y, double scale)
363  {
364  // Calculate the correct offsets and dimensions
365  double x_offset = offset_x_;
366  double y_offset = offset_y_;
367  double width = width_;
368  double height = height_;
369  if (units_ == PERCENT)
370  {
371  x_offset = offset_x_ * canvas_->width() / 100.0;
372  y_offset = offset_y_ * canvas_->height() / 100.0;
373  width = width_ * canvas_->width() / 100.0;
374  height = height_ * canvas_->height() / 100.0;
375  }
376 
377  // Scale the source image if necessary
378  if (width != last_width_ || height != last_height_)
379  {
380  ScaleImage(width, height);
381  }
382 
383  // Calculate the correct render position
384  double x_pos = 0;
385  double y_pos = 0;
386  if (anchor_ == TOP_LEFT)
387  {
388  x_pos = x_offset;
389  y_pos = y_offset;
390  }
391  else if (anchor_ == TOP_CENTER)
392  {
393  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
394  y_pos = y_offset;
395  }
396  else if (anchor_ == TOP_RIGHT)
397  {
398  x_pos = canvas_->width() - width - x_offset;
399  y_pos = y_offset;
400  }
401  else if (anchor_ == CENTER_LEFT)
402  {
403  x_pos = x_offset;
404  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
405  }
406  else if (anchor_ == CENTER)
407  {
408  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
409  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
410  }
411  else if (anchor_ == CENTER_RIGHT)
412  {
413  x_pos = canvas_->width() - width - x_offset;
414  y_pos = (canvas_->height() - height) / 2.0 + y_offset;
415  }
416  else if (anchor_ == BOTTOM_LEFT)
417  {
418  x_pos = x_offset;
419  y_pos = canvas_->height() - height - y_offset;
420  }
421  else if (anchor_ == BOTTOM_CENTER)
422  {
423  x_pos = (canvas_->width() - width) / 2.0 + x_offset;
424  y_pos = canvas_->height() - height - y_offset;
425  }
426  else if (anchor_ == BOTTOM_RIGHT)
427  {
428  x_pos = canvas_->width() - width - x_offset;
429  y_pos = canvas_->height() - height - y_offset;
430  }
431 
432  glMatrixMode(GL_PROJECTION);
433  glPushMatrix();
434  glLoadIdentity();
435  glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f);
436 
437  glRasterPos2d(x_pos, y_pos);
438 
440 
441  glPopMatrix();
442 
443  last_width_ = width;
444  last_height_ = height;
445  }
446 
447  void DisparityPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
448  {
449  if (node["topic"])
450  {
451  std::string topic;
452  node["topic"] >> topic;
453  ui_.topic->setText(topic.c_str());
454  TopicEdited();
455  }
456 
457  if (node["anchor"])
458  {
459  std::string anchor;
460  node["anchor"] >> anchor;
461  ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str()));
462  SetAnchor(anchor.c_str());
463  }
464 
465  if (node["units"])
466  {
467  std::string units;
468  node["units"] >> units;
469  ui_.units->setCurrentIndex(ui_.units->findText(units.c_str()));
470  SetUnits(units.c_str());
471  }
472 
473  if (node["offset_x"])
474  {
475  node["offset_x"] >> offset_x_;
476  ui_.offsetx->setValue(static_cast<int>(offset_x_));
477  }
478 
479  if (node["offset_y"])
480  {
481  node["offset_y"] >> offset_y_;
482  ui_.offsety->setValue(static_cast<int>(offset_y_));
483  }
484 
485  if (node["width"])
486  {
487  node["width"] >> width_;
488  ui_.width->setValue(static_cast<int>(width_));
489  }
490 
491  if (node["height"])
492  {
493  node["height"] >> height_;
494  ui_.height->setValue(static_cast<int>(height_));
495  }
496  }
497 
498  void DisparityPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
499  {
500  emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
501  emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_);
502  emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_);
503  emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_;
504  emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_;
505  emitter << YAML::Key << "width" << YAML::Value << width_;
506  emitter << YAML::Key << "height" << YAML::Value << height_;
507  }
508 
510  {
511  std::string anchor_string = "top left";
512 
513  if (anchor == TOP_LEFT)
514  {
515  anchor_string = "top left";
516  }
517  else if (anchor == TOP_CENTER)
518  {
519  anchor_string = "top center";
520  }
521  else if (anchor == TOP_RIGHT)
522  {
523  anchor_string = "top right";
524  }
525  else if (anchor == CENTER_LEFT)
526  {
527  anchor_string = "center left";
528  }
529  else if (anchor == CENTER)
530  {
531  anchor_string = "center";
532  }
533  else if (anchor == CENTER_RIGHT)
534  {
535  anchor_string = "center right";
536  }
537  else if (anchor == BOTTOM_LEFT)
538  {
539  anchor_string = "bottom left";
540  }
541  else if (anchor == BOTTOM_CENTER)
542  {
543  anchor_string = "bottom center";
544  }
545  else if (anchor == BOTTOM_RIGHT)
546  {
547  anchor_string = "bottom right";
548  }
549 
550  return anchor_string;
551  }
552 
554  {
555  std::string units_string = "pixels";
556 
557  if (units == PIXELS)
558  {
559  units_string = "pixels";
560  }
561  else if (units == PERCENT)
562  {
563  units_string = "percent";
564  }
565 
566  return units_string;
567  }
568 
569  const unsigned char DisparityPlugin::COLOR_MAP[768] =
570  { 150, 150, 150,
571  107, 0, 12,
572  106, 0, 18,
573  105, 0, 24,
574  103, 0, 30,
575  102, 0, 36,
576  101, 0, 42,
577  99, 0, 48,
578  98, 0, 54,
579  97, 0, 60,
580  96, 0, 66,
581  94, 0, 72,
582  93, 0, 78,
583  92, 0, 84,
584  91, 0, 90,
585  89, 0, 96,
586  88, 0, 102,
587  87, 0, 108,
588  85, 0, 114,
589  84, 0, 120,
590  83, 0, 126,
591  82, 0, 131,
592  80, 0, 137,
593  79, 0, 143,
594  78, 0, 149,
595  77, 0, 155,
596  75, 0, 161,
597  74, 0, 167,
598  73, 0, 173,
599  71, 0, 179,
600  70, 0, 185,
601  69, 0, 191,
602  68, 0, 197,
603  66, 0, 203,
604  65, 0, 209,
605  64, 0, 215,
606  62, 0, 221,
607  61, 0, 227,
608  60, 0, 233,
609  59, 0, 239,
610  57, 0, 245,
611  56, 0, 251,
612  55, 0, 255,
613  54, 0, 255,
614  52, 0, 255,
615  51, 0, 255,
616  50, 0, 255,
617  48, 0, 255,
618  47, 0, 255,
619  46, 0, 255,
620  45, 0, 255,
621  43, 0, 255,
622  42, 0, 255,
623  41, 0, 255,
624  40, 0, 255,
625  38, 0, 255,
626  37, 0, 255,
627  36, 0, 255,
628  34, 0, 255,
629  33, 0, 255,
630  32, 0, 255,
631  31, 0, 255,
632  29, 0, 255,
633  28, 0, 255,
634  27, 0, 255,
635  26, 0, 255,
636  24, 0, 255,
637  23, 0, 255,
638  22, 0, 255,
639  20, 0, 255,
640  19, 0, 255,
641  18, 0, 255,
642  17, 0, 255,
643  15, 0, 255,
644  14, 0, 255,
645  13, 0, 255,
646  11, 0, 255,
647  10, 0, 255,
648  9, 0, 255,
649  8, 0, 255,
650  6, 0, 255,
651  5, 0, 255,
652  4, 0, 255,
653  3, 0, 255,
654  1, 0, 255,
655  0, 4, 255,
656  0, 10, 255,
657  0, 16, 255,
658  0, 22, 255,
659  0, 28, 255,
660  0, 34, 255,
661  0, 40, 255,
662  0, 46, 255,
663  0, 52, 255,
664  0, 58, 255,
665  0, 64, 255,
666  0, 70, 255,
667  0, 76, 255,
668  0, 82, 255,
669  0, 88, 255,
670  0, 94, 255,
671  0, 100, 255,
672  0, 106, 255,
673  0, 112, 255,
674  0, 118, 255,
675  0, 124, 255,
676  0, 129, 255,
677  0, 135, 255,
678  0, 141, 255,
679  0, 147, 255,
680  0, 153, 255,
681  0, 159, 255,
682  0, 165, 255,
683  0, 171, 255,
684  0, 177, 255,
685  0, 183, 255,
686  0, 189, 255,
687  0, 195, 255,
688  0, 201, 255,
689  0, 207, 255,
690  0, 213, 255,
691  0, 219, 255,
692  0, 225, 255,
693  0, 231, 255,
694  0, 237, 255,
695  0, 243, 255,
696  0, 249, 255,
697  0, 255, 255,
698  0, 255, 249,
699  0, 255, 243,
700  0, 255, 237,
701  0, 255, 231,
702  0, 255, 225,
703  0, 255, 219,
704  0, 255, 213,
705  0, 255, 207,
706  0, 255, 201,
707  0, 255, 195,
708  0, 255, 189,
709  0, 255, 183,
710  0, 255, 177,
711  0, 255, 171,
712  0, 255, 165,
713  0, 255, 159,
714  0, 255, 153,
715  0, 255, 147,
716  0, 255, 141,
717  0, 255, 135,
718  0, 255, 129,
719  0, 255, 124,
720  0, 255, 118,
721  0, 255, 112,
722  0, 255, 106,
723  0, 255, 100,
724  0, 255, 94,
725  0, 255, 88,
726  0, 255, 82,
727  0, 255, 76,
728  0, 255, 70,
729  0, 255, 64,
730  0, 255, 58,
731  0, 255, 52,
732  0, 255, 46,
733  0, 255, 40,
734  0, 255, 34,
735  0, 255, 28,
736  0, 255, 22,
737  0, 255, 16,
738  0, 255, 10,
739  0, 255, 4,
740  2, 255, 0,
741  8, 255, 0,
742  14, 255, 0,
743  20, 255, 0,
744  26, 255, 0,
745  32, 255, 0,
746  38, 255, 0,
747  44, 255, 0,
748  50, 255, 0,
749  56, 255, 0,
750  62, 255, 0,
751  68, 255, 0,
752  74, 255, 0,
753  80, 255, 0,
754  86, 255, 0,
755  92, 255, 0,
756  98, 255, 0,
757  104, 255, 0,
758  110, 255, 0,
759  116, 255, 0,
760  122, 255, 0,
761  128, 255, 0,
762  133, 255, 0,
763  139, 255, 0,
764  145, 255, 0,
765  151, 255, 0,
766  157, 255, 0,
767  163, 255, 0,
768  169, 255, 0,
769  175, 255, 0,
770  181, 255, 0,
771  187, 255, 0,
772  193, 255, 0,
773  199, 255, 0,
774  205, 255, 0,
775  211, 255, 0,
776  217, 255, 0,
777  223, 255, 0,
778  229, 255, 0,
779  235, 255, 0,
780  241, 255, 0,
781  247, 255, 0,
782  253, 255, 0,
783  255, 251, 0,
784  255, 245, 0,
785  255, 239, 0,
786  255, 233, 0,
787  255, 227, 0,
788  255, 221, 0,
789  255, 215, 0,
790  255, 209, 0,
791  255, 203, 0,
792  255, 197, 0,
793  255, 191, 0,
794  255, 185, 0,
795  255, 179, 0,
796  255, 173, 0,
797  255, 167, 0,
798  255, 161, 0,
799  255, 155, 0,
800  255, 149, 0,
801  255, 143, 0,
802  255, 137, 0,
803  255, 131, 0,
804  255, 126, 0,
805  255, 120, 0,
806  255, 114, 0,
807  255, 108, 0,
808  255, 102, 0,
809  255, 96, 0,
810  255, 90, 0,
811  255, 84, 0,
812  255, 78, 0,
813  255, 72, 0,
814  255, 66, 0,
815  255, 60, 0,
816  255, 54, 0,
817  255, 48, 0,
818  255, 42, 0,
819  255, 36, 0,
820  255, 30, 0,
821  255, 24, 0,
822  255, 18, 0,
823  255, 12, 0,
824  255, 6, 0,
825  255, 0, 0,
826  };
827 }
828 
d
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NULL
void PrintInfo(const std::string &message)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
bool Visible() const
ros::NodeHandle node_
void disparityCallback(const stereo_msgs::DisparityImageConstPtr &image)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void Draw(double x, double y, double scale)
void PrintError(const std::string &message)
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 PrintWarning(const std::string &message)
std::string UnitsToString(Units units)
cv::Mat_< cv::Vec3b > disparity_color_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
bool Initialize(QGLWidget *canvas)
std::string AnchorToString(Anchor anchor)
void ScaleImage(double width, double height)
#define ROS_INFO(...)
const std::string TYPE_32FC1
static const unsigned char COLOR_MAP[]
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
stereo_msgs::DisparityImage disparity_
void VisibleChanged(bool visible)
void LoadConfig(const YAML::Node &node, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
QWidget * GetConfigWidget(QWidget *parent)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Fri Mar 19 2021 02:44:32