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