PlotWidget.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (C) 2015 by Ralf Kaestner *
3  * ralf.kaestner@gmail.com *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the Lesser GNU General Public License as published by*
7  * the Free Software Foundation; either version 3 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * Lesser GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the Lesser GNU General Public License *
16  * along with this program. If not, see <http://www.gnu.org/licenses/>. *
17  ******************************************************************************/
18 
19 #include <QDragEnterEvent>
20 #include <QDropEvent>
21 #include <QFile>
22 #include <QFileDialog>
23 #include <QFontMetrics>
24 #include <QPainter>
25 #include <QTextStream>
26 #include <QMimeData>
27 
28 #include <qwt/qwt_plot_canvas.h>
29 #include <qwt/qwt_plot_curve.h>
30 #include <qwt/qwt_plot_picker.h>
31 #include <qwt/qwt_plot_renderer.h>
32 #include <qwt/qwt_scale_widget.h>
33 #include <qwt/qwt_plot.h>
34 
35 #include <ros/package.h>
36 
46 
47 #include <ui_PlotWidget.h>
48 
50 
51 namespace rqt_multiplot {
52 
53 /*****************************************************************************/
54 /* Constructors and Destructor */
55 /*****************************************************************************/
56 
57 PlotWidget::PlotWidget(QWidget* parent) :
58  QWidget(parent),
59  ui_(new Ui::PlotWidget()),
60  timer_(new QTimer(this)),
61  menuImportExport_(new QMenu(this)),
62  config_(0),
63  broker_(0),
64  legend_(0),
65  cursor_(0),
66  panner_(0),
67  magnifier_(0),
68  zoomer_(0),
69  paused_(true),
70  rescale_(false),
71  replot_(false),
72  state_(Normal) {
73  qRegisterMetaType<BoundingRectangle>("BoundingRectangle");
74 
75  ui_->setupUi(this);
76 
77  setAcceptDrops(true);
78 
79  runIcon_ = QIcon(QString::fromStdString(ros::package::getPath(
80  "rqt_multiplot").append("/resource/16x16/run.png")));
81  pauseIcon_ = QIcon(QString::fromStdString(ros::package::getPath(
82  "rqt_multiplot").append("/resource/16x16/pause.png")));
83  normalIcon_ = QIcon(QString::fromStdString(ros::package::getPath(
84  "rqt_multiplot").append("/resource/16x16/zoom_in.png")));
85  maximizedIcon_ = QIcon(QString::fromStdString(ros::package::getPath(
86  "rqt_multiplot").append("/resource/16x16/zoom_out.png")));
87 
88  ui_->pushButtonRunPause->setIcon(runIcon_);
89  ui_->pushButtonClear->setIcon(
90  QIcon(QString::fromStdString(ros::package::getPath("rqt_multiplot").
91  append("/resource/16x16/clear.png"))));
92  ui_->pushButtonImportExport->setIcon(
93  QIcon(QString::fromStdString(ros::package::getPath("rqt_multiplot").
94  append("/resource/16x16/eject.png"))));
95  ui_->pushButtonSetup->setIcon(
96  QIcon(QString::fromStdString(ros::package::getPath("rqt_multiplot").
97  append("/resource/16x16/setup.png"))));
98  ui_->pushButtonState->setIcon(normalIcon_);
99 
100  ui_->plot->setAutoReplot(false);
101  static_cast<QFrame*>(ui_->plot->canvas())->setFrameStyle(QFrame::NoFrame);
102 
103  ui_->plot->enableAxis(QwtPlot::xTop);
104  ui_->plot->enableAxis(QwtPlot::yRight);
105 
106  ui_->plot->setAxisAutoScale(QwtPlot::yLeft, false);
107  ui_->plot->setAxisAutoScale(QwtPlot::yRight, false);
108  ui_->plot->setAxisAutoScale(QwtPlot::xTop, false);
109  ui_->plot->setAxisAutoScale(QwtPlot::xBottom, false);
110 
111  ui_->plot->axisScaleDraw(QwtPlot::xTop)->enableComponent(
112  QwtAbstractScaleDraw::Labels, false);
113  ui_->plot->axisScaleDraw(QwtPlot::yRight)->enableComponent(
114  QwtAbstractScaleDraw::Labels, false);
115 
116  ui_->horizontalSpacerRight->changeSize(
117  ui_->plot->axisWidget(QwtPlot::yRight)->width()-5, 20);
118 
119  timer_->setInterval(1e3/30.0);
120  timer_->start();
121 
122  menuImportExport_->addAction("Export to image file...", this,
124  menuImportExport_->addAction("Export to text file...", this,
126 
127  QwtPlotCanvas* canvas = static_cast<QwtPlotCanvas*>(ui_->plot->canvas());
128  cursor_ = new PlotCursor(canvas);
129  magnifier_ = new PlotMagnifier(canvas);
130  panner_ = new PlotPanner(canvas);
131  zoomer_ = new PlotZoomer(canvas);
132  zoomer_->setTrackerMode(QwtPicker::AlwaysOff);
133 
134  #if QWT_VERSION >= 0x060100
135  currentBounds_.getMinimum().setX(ui_->plot->axisScaleDiv(
136  QwtPlot::xBottom).lowerBound());
137  currentBounds_.getMinimum().setY(ui_->plot->axisScaleDiv(
138  QwtPlot::yLeft).lowerBound());
139  currentBounds_.getMaximum().setX(ui_->plot->axisScaleDiv(
140  QwtPlot::xBottom).upperBound());
141  currentBounds_.getMaximum().setY(ui_->plot->axisScaleDiv(
142  QwtPlot::yLeft).upperBound());
143  #else
144  currentBounds_.getMinimum().setX(ui_->plot->axisScaleDiv(
145  QwtPlot::xBottom)->lowerBound());
146  currentBounds_.getMinimum().setY(ui_->plot->axisScaleDiv(
147  QwtPlot::yLeft)->lowerBound());
148  currentBounds_.getMaximum().setX(ui_->plot->axisScaleDiv(
149  QwtPlot::xBottom)->upperBound());
150  currentBounds_.getMaximum().setY(ui_->plot->axisScaleDiv(
151  QwtPlot::yLeft)->upperBound());
152  #endif
153 
154  connect(ui_->lineEditTitle, SIGNAL(textChanged(const QString&)), this,
155  SLOT(lineEditTitleTextChanged(const QString&)));
156  connect(ui_->lineEditTitle, SIGNAL(editingFinished()), this,
158 
159  connect(ui_->pushButtonRunPause, SIGNAL(clicked()), this,
160  SLOT(pushButtonRunPauseClicked()));
161  connect(ui_->pushButtonClear, SIGNAL(clicked()), this,
162  SLOT(pushButtonClearClicked()));
163  connect(ui_->pushButtonSetup, SIGNAL(clicked()), this,
164  SLOT(pushButtonSetupClicked()));
165  connect(ui_->pushButtonImportExport, SIGNAL(clicked()), this,
167  connect(ui_->pushButtonState, SIGNAL(clicked()), this,
168  SLOT(pushButtonStateClicked()));
169 
170  connect(ui_->plot->axisWidget(QwtPlot::xBottom),
171  SIGNAL(scaleDivChanged()), this, SLOT(plotXBottomScaleDivChanged()));
172  connect(ui_->plot->axisWidget(QwtPlot::yLeft),
173  SIGNAL(scaleDivChanged()), this, SLOT(plotYLeftScaleDivChanged()));
174 
175  connect(timer_, SIGNAL(timeout()), this, SLOT(timerTimeout()));
176 
177  ui_->plot->axisWidget(QwtPlot::yLeft)->installEventFilter(this);
178  ui_->plot->axisWidget(QwtPlot::yRight)->installEventFilter(this);
179 }
180 
182  delete ui_;
183 }
184 
185 /*****************************************************************************/
186 /* Accessors */
187 /*****************************************************************************/
188 
190  if (config != config_) {
191  if (config_) {
192  disconnect(config_, SIGNAL(titleChanged(const QString&)), this,
193  SLOT(configTitleChanged(const QString&)));
194  disconnect(config_, SIGNAL(curveAdded(size_t)), this,
195  SLOT(configCurveAdded(size_t)));
196  disconnect(config_, SIGNAL(curveRemoved(size_t)), this,
197  SLOT(configCurveRemoved(size_t)));
198  disconnect(config_, SIGNAL(curvesCleared()), this,
199  SLOT(configCurvesCleared()));
200  disconnect(config_, SIGNAL(curveConfigChanged(size_t)), this,
201  SLOT(configCurveConfigChanged(size_t)));
203  SIGNAL(changed()), this, SLOT(configXAxisConfigChanged()));
205  SIGNAL(changed()), this, SLOT(configYAxisConfigChanged()));
206  disconnect(config_->getLegendConfig(), SIGNAL(changed()), this,
207  SLOT(configLegendConfigChanged()));
208  disconnect(config_, SIGNAL(plotRateChanged(double)), this,
209  SLOT(configPlotRateChanged(double)));
210 
212  }
213 
214  config_ = config;
215 
216  if (config) {
217  connect(config, SIGNAL(titleChanged(const QString&)), this,
218  SLOT(configTitleChanged(const QString&)));
219  connect(config, SIGNAL(curveAdded(size_t)), this,
220  SLOT(configCurveAdded(size_t)));
221  connect(config, SIGNAL(curveRemoved(size_t)), this,
222  SLOT(configCurveRemoved(size_t)));
223  connect(config, SIGNAL(curvesCleared()), this,
224  SLOT(configCurvesCleared()));
225  connect(config, SIGNAL(curveConfigChanged(size_t)), this,
226  SLOT(configCurveConfigChanged(size_t)));
227  connect(config->getAxesConfig()->getAxisConfig(PlotAxesConfig::X),
228  SIGNAL(changed()), this, SLOT(configXAxisConfigChanged()));
229  connect(config->getAxesConfig()->getAxisConfig(PlotAxesConfig::Y),
230  SIGNAL(changed()), this, SLOT(configYAxisConfigChanged()));
231  connect(config->getLegendConfig(), SIGNAL(changed()), this,
232  SLOT(configLegendConfigChanged()));
233  connect(config, SIGNAL(plotRateChanged(double)), this,
234  SLOT(configPlotRateChanged(double)));
235 
236  configTitleChanged(config->getTitle());
241 
242  for (size_t index = 0; index < config->getNumCurves(); ++index)
243  configCurveAdded(index);
244  }
245  }
246 }
247 
249  return config_;
250 }
251 
253  if (broker != broker_) {
254  broker_ = broker;
255 
256  for (size_t index = 0; index < curves_.count(); ++index)
257  curves_[index]->setBroker(broker);
258  }
259 }
260 
262  return broker_;
263 }
264 
266  return cursor_;
267 }
268 
270  BoundingRectangle bounds;
271 
272  for (size_t index = 0; index < curves_.count(); ++index)
273  bounds += curves_[index]->getPreferredScale();
274 
275  return bounds;
276 }
277 
279  if (bounds != currentBounds_) {
280  if (bounds.getMaximum().x() == bounds.getMinimum().x())
281  ui_->plot->setAxisScale(QwtPlot::xBottom, bounds.getMinimum().x() - 0.1,
282  bounds.getMaximum().x() + 0.1);
283  else if (bounds.getMaximum().x() > bounds.getMinimum().x())
284  ui_->plot->setAxisScale(QwtPlot::xBottom, bounds.getMinimum().x(),
285  bounds.getMaximum().x());
286  if (bounds.getMaximum().y() == bounds.getMinimum().y())
287  ui_->plot->setAxisScale(QwtPlot::yLeft, bounds.getMinimum().y() - 0.1,
288  bounds.getMaximum().y() + 0.1);
289  else if (bounds.getMaximum().y() > bounds.getMinimum().y())
290  ui_->plot->setAxisScale(QwtPlot::yLeft, bounds.getMinimum().y(),
291  bounds.getMaximum().y());
292 
293  rescale_ = false;
294 
295  forceReplot();
296  }
297 }
298 
300  return currentBounds_;
301 }
302 
303 bool PlotWidget::isPaused() const {
304  return paused_;
305 }
306 
308  return replot_;
309 }
310 
312  if ((state != state_) && canChangeState()) {
313  state_ = state;
314 
315  if (state == Maximized)
316  ui_->pushButtonState->setIcon(maximizedIcon_);
317  else
318  ui_->pushButtonState->setIcon(normalIcon_);
319 
320  emit stateChanged(state);
321  }
322 }
323 
325  return state_;
326 }
327 
329  ui_->pushButtonState->setEnabled(can);
330 }
331 
333  return ui_->pushButtonState->isEnabled();
334 }
335 
336 /*****************************************************************************/
337 /* Methods */
338 /*****************************************************************************/
339 
341  if (paused_) {
342  paused_ = false;
343 
344  for (size_t index = 0; index < curves_.count(); ++index)
345  curves_[index]->run();
346 
347  ui_->pushButtonRunPause->setIcon(pauseIcon_);
348 
349  emit pausedChanged(false);
350  }
351 }
352 
354  if (!paused_) {
355  for (size_t index = 0; index < curves_.count(); ++index)
356  curves_[index]->pause();
357 
358  paused_ = true;
359 
360  ui_->pushButtonRunPause->setIcon(runIcon_);
361 
362  emit pausedChanged(true);
363  }
364 }
365 
367  for (size_t index = 0; index < curves_.count(); ++index)
368  curves_[index]->clear();
369 
370  forceReplot();
371 
372  emit cleared();
373 }
374 
376  replot_ = true;
377 }
378 
380  BoundingRectangle preferredBounds = getPreferredScale();
381 
382  if (rescale_) {
383  emit preferredScaleChanged(preferredBounds);
384 
385  rescale_ = false;
386  }
387 
388  zoomer_->setZoomBase(preferredBounds.getRectangle());
389 
390  ui_->plot->replot();
391 
392  replot_ = false;
393 }
394 
395 void PlotWidget::renderToPixmap(QPixmap& pixmap, const QRectF& bounds) {
396  QRectF plotBounds = bounds;
397 
398  if (plotBounds.isEmpty())
399  plotBounds = QRectF(0, 0, pixmap.width(), pixmap.height());
400 
401  QwtPlotRenderer renderer;
402 
403  renderer.setDiscardFlag(QwtPlotRenderer::DiscardBackground, true);
404  renderer.setDiscardFlag(QwtPlotRenderer::DiscardCanvasBackground, true);
405 
406  QPainter painter(&pixmap);
407  size_t textHeight = 0;
408 
409  if (config_) {
410  textHeight = painter.fontMetrics().boundingRect(config_->
411  getTitle()).height();
412 
413  painter.drawText(QRectF(plotBounds.x(), plotBounds.y(),
414  plotBounds.width(), textHeight), Qt::AlignHCenter |
415  Qt::AlignVCenter, config_->getTitle());
416  }
417 
418  renderer.render(ui_->plot, &painter, QRectF(plotBounds.x(),
419  plotBounds.y()+textHeight+10, plotBounds.width(), plotBounds.
420  height()-textHeight-10));
421 }
422 
423 void PlotWidget::writeFormattedCurveData(QList<QStringList>& formattedData) {
424  formattedData.clear();
425 
426  for (size_t index = 0; index < curves_.count(); ++index) {
427  QStringList formattedX, formattedY;
428 
429  curves_[index]->getData()->writeFormatted(formattedX, formattedY);
430 
431  formattedData.append(formattedX);
432  formattedData.append(formattedY);
433  }
434 }
435 
437  formattedAxisTitles) {
438  formattedAxisTitles.clear();
439 
440  for (size_t index = 0; index < curves_.count(); ++index) {
441  CurveAxisConfig* xAxisConfig = curves_[index]->getConfig()->
442  getAxisConfig(CurveConfig::X);
443  CurveAxisConfig* yAxisConfig = curves_[index]->getConfig()->
444  getAxisConfig(CurveConfig::Y);
445 
446  QString xAxisTitle = xAxisConfig->getTopic();
447  QString yAxisTitle = yAxisConfig->getTopic();
448 
449  if (xAxisConfig->getFieldType() == CurveAxisConfig::MessageData)
450  xAxisTitle += "/"+xAxisConfig->getField();
451  else
452  xAxisTitle += "/recceipt_time";
453 
454  if (yAxisConfig->getFieldType() == CurveAxisConfig::MessageData)
455  yAxisTitle += "/"+yAxisConfig->getField();
456  else
457  yAxisTitle += "/recceipt_time";
458 
459  formattedAxisTitles.append(xAxisTitle);
460  formattedAxisTitles.append(yAxisTitle);
461  }
462 }
463 
464 void PlotWidget::saveToImageFile(const QString& fileName) {
465  QPixmap pixmap(1280, 1024);
466 
467  pixmap.fill(Qt::transparent);
468  renderToPixmap(pixmap);
469 
470  pixmap.save(fileName, "PNG");
471 }
472 
473 void PlotWidget::saveToTextFile(const QString& fileName) {
474  QFile file(fileName);
475 
476  if (file.open(QIODevice::WriteOnly)) {
477  QStringList formattedAxisTitles;
478  QList<QStringList> formattedData;
479 
480  writeFormattedCurveAxisTitles(formattedAxisTitles);
481  writeFormattedCurveData(formattedData);
482 
483  QTextStream stream(&file);
484 
485  stream << "# " << formattedAxisTitles.join(", ") << "\n";
486 
487  size_t row = 0;
488 
489  while (true) {
490  QStringList dataLineParts;
491  bool finished = true;
492 
493  for (size_t column = 0; column < formattedData.count(); ++column) {
494  if (row < formattedData[column].count()) {
495  dataLineParts.append(formattedData[column][row]);
496  finished &= false;
497  }
498  else
499  dataLineParts.append(QString());
500  }
501 
502  if (!finished) {
503  stream << dataLineParts.join(", ") << "\n";
504  row++;
505  }
506  else
507  break;
508  }
509  }
510 }
511 
512 void PlotWidget::dragEnterEvent(QDragEnterEvent* event) {
513  if (event->mimeData()->hasFormat(CurveConfig::MimeType) &&
514  (event->source() != legend_) && config_)
515  event->acceptProposedAction();
516  else
517  event->ignore();
518 }
519 
520 void PlotWidget::dropEvent(QDropEvent* event) {
521  if (event->mimeData()->hasFormat(CurveConfig::MimeType) &&
522  (event->source() != legend_) && config_) {
523  QByteArray data = event->mimeData()->data(CurveConfig::MimeType);
524  QDataStream stream(&data, QIODevice::ReadOnly);
525 
526  CurveConfig* curveConfig = config_->addCurve();
527  stream >> *curveConfig;
528 
529  while (config_->findCurves(curveConfig->getTitle()).count() > 1)
530  curveConfig->setTitle("Copy of "+curveConfig->getTitle());
531 
532  event->acceptProposedAction();
533  }
534  else
535  event->ignore();
536 }
537 
538 bool PlotWidget::eventFilter(QObject* object, QEvent* event) {
539  if ((object == ui_->plot->axisWidget(QwtPlot::yLeft)) &&
540  (event->type() == QEvent::Resize)) {
541  ui_->horizontalSpacerLeft->changeSize(
542  ui_->plot->axisWidget(QwtPlot::yLeft)->width(), 20);
543  layout()->update();
544  }
545  else if ((object == ui_->plot->axisWidget(QwtPlot::yRight)) &&
546  (event->type() == QEvent::Resize)) {
547  ui_->horizontalSpacerRight->changeSize(
548  ui_->plot->axisWidget(QwtPlot::yRight)->width()-5, 20);
549  layout()->update();
550  }
551 
552  return false;
553 }
554 
556  QwtPlot::Axis plotAxis = (axis == PlotAxesConfig::Y) ?
557  QwtPlot::yLeft : QwtPlot::xBottom;
558  CurveConfig::Axis curveAxis = (axis == PlotAxesConfig::Y) ?
560 
561  PlotAxisConfig* plotAxisConfig = config_->getAxesConfig()->
562  getAxisConfig(axis);
563 
564  if (plotAxisConfig->isTitleVisible()) {
565  if (plotAxisConfig->getTitleType() == PlotAxisConfig::AutoTitle) {
566  QStringList titleParts;
567 
568  for (size_t index = 0; index < config_->getNumCurves(); ++index) {
569  CurveAxisConfig* curveAxisConfig = config_->getCurveConfig(index)->
570  getAxisConfig(curveAxis);
571 
572  QString titlePart = curveAxisConfig->getTopic();
573  if (curveAxisConfig->getFieldType() == CurveAxisConfig::MessageData)
574  titlePart += "/"+curveAxisConfig->getField();
575  else
576  titlePart += "/receipt_time";
577 
578  if (!titleParts.contains(titlePart))
579  titleParts.append(titlePart);
580  }
581 
582  ui_->plot->setAxisTitle(plotAxis, QwtText(titleParts.join(", ")));
583  }
584  else
585  ui_->plot->setAxisTitle(plotAxis, QwtText(plotAxisConfig->
586  getCustomTitle()));
587  }
588  else
589  ui_->plot->setAxisTitle(plotAxis, QwtText());
590 }
591 
592 /*****************************************************************************/
593 /* Slots */
594 /*****************************************************************************/
595 
597  if (replot_)
598  forceReplot();
599 }
600 
601 void PlotWidget::configTitleChanged(const QString& title) {
602  ui_->lineEditTitle->setText(config_->getTitle());
603 }
604 
605 void PlotWidget::configCurveAdded(size_t index) {
606  PlotCurve* curve = new PlotCurve(this);
607 
608  curve->attach(ui_->plot);
609  curve->setConfig(config_->getCurveConfig(index));
610  curve->setBroker(broker_);
611 
612  connect(curve, SIGNAL(replotRequested()), this,
613  SLOT(curveReplotRequested()));
614 
615  curves_.insert(index, curve);
616 
619 
620  forceReplot();
621 }
622 
623 void PlotWidget::configCurveRemoved(size_t index) {
624  curves_[index]->detach();
625 
626  delete curves_[index];
627 
628  curves_.remove(index);
629 
632 
633  forceReplot();
634 }
635 
637  for (size_t index = 0; index < curves_.count(); ++index) {
638  curves_[index]->detach();
639 
640  delete curves_[index];
641  }
642 
643  curves_.clear();
644 
647 
648  forceReplot();
649 }
650 
654 }
655 
658 }
659 
662 }
663 
665  if (!legend_ && config_->getLegendConfig()->isVisible()) {
666  legend_ = new PlotLegend(this);
667  ui_->plot->insertLegend(legend_, QwtPlot::TopLegend);
668  }
669  else if (legend_ && !config_->getLegendConfig()->isVisible()) {
670  ui_->plot->insertLegend(0);
671  legend_ = 0;
672  }
673 }
674 
676  timer_->setInterval(1e3/rate);
677 }
678 
680  rescale_ = true;
681 
682  requestReplot();
683 }
684 
685 void PlotWidget::lineEditTitleTextChanged(const QString& text) {
686  QFontMetrics fontMetrics(ui_->lineEditTitle->font());
687 
688  ui_->lineEditTitle->setMinimumWidth(
689  std::max(100, fontMetrics.width(text)+10));
690 }
691 
693  if (config_)
694  config_->setTitle(ui_->lineEditTitle->text());
695 }
696 
698  if (paused_)
699  run();
700  else
701  pause();
702 }
703 
705  clear();
706 }
707 
709  if (config_) {
710  PlotConfigDialog dialog(this);
711 
712  dialog.setWindowTitle(config_->getTitle().isEmpty() ?
713  "Configure Plot" :
714  "Configure \""+config_->getTitle()+"\"");
715  dialog.getWidget()->setConfig(*config_);
716 
717  if (dialog.exec() == QDialog::Accepted)
718  *config_ = dialog.getWidget()->getConfig();
719  }
720 }
721 
723  menuImportExport_->popup(QCursor::pos());
724 }
725 
727  if (state_ == Maximized)
728  setState(Normal);
729  else
731 }
732 
734  QFileDialog dialog(this, "Save Image File", QDir::homePath(),
735  "Portable Network Graphics (*.png)");
736 
737  dialog.setAcceptMode(QFileDialog::AcceptSave);
738  dialog.setFileMode(QFileDialog::AnyFile);
739  dialog.selectFile("rqt_multiplot.png");
740 
741  if (dialog.exec() == QDialog::Accepted)
742  saveToImageFile(dialog.selectedFiles().first());
743 }
744 
746  QFileDialog dialog(this, "Save Text File", QDir::homePath(),
747  "Text file (*.txt)");
748 
749  dialog.setAcceptMode(QFileDialog::AcceptSave);
750  dialog.setFileMode(QFileDialog::AnyFile);
751  dialog.selectFile("rqt_multiplot.txt");
752 
753  if (dialog.exec() == QDialog::Accepted)
754  saveToTextFile(dialog.selectedFiles().first());
755 }
756 
758  #if QWT_VERSION >= 0x060100
759  const QwtScaleDiv& scale = ui_->plot->axisScaleDiv(QwtPlot::xBottom);
760  #else
761  const QwtScaleDiv& scale = *ui_->plot->axisScaleDiv(QwtPlot::xBottom);
762  #endif
763 
764  ui_->plot->setAxisScaleDiv(QwtPlot::xTop, scale);
765 
766  currentBounds_.getMinimum().setX(scale.lowerBound());
767  currentBounds_.getMaximum().setX(scale.upperBound());
768 
770 }
771 
773  #if QWT_VERSION >= 0x060100
774  const QwtScaleDiv& scale = ui_->plot->axisScaleDiv(QwtPlot::yLeft);
775  #else
776  const QwtScaleDiv& scale = *ui_->plot->axisScaleDiv(QwtPlot::yLeft);
777  #endif
778 
779  ui_->plot->setAxisScaleDiv(QwtPlot::yRight, scale);
780 
781  currentBounds_.getMinimum().setY(scale.lowerBound());
782  currentBounds_.getMaximum().setY(scale.upperBound());
783 
785 }
786 
787 }
const PlotConfig & getConfig() const
const QString & getTopic() const
void setCurrentScale(const BoundingRectangle &bounds)
Definition: PlotWidget.cpp:278
static const QString MimeType
Definition: CurveConfig.h:41
PlotAxesConfig * getAxesConfig() const
Definition: PlotConfig.cpp:79
QVector< PlotCurve * > curves_
Definition: PlotWidget.h:115
QVector< CurveConfig * > findCurves(const QString &title) const
Definition: PlotConfig.cpp:145
bool eventFilter(QObject *object, QEvent *event)
Definition: PlotWidget.cpp:538
void lineEditTitleTextChanged(const QString &text)
Definition: PlotWidget.cpp:685
PlotConfigWidget * getWidget() const
void setConfig(const PlotConfig &config)
MessageBroker * getBroker() const
Definition: PlotWidget.cpp:261
CurveConfig * addCurve()
Definition: PlotConfig.cpp:104
void pausedChanged(bool paused)
void attach(QwtPlot *plot)
Definition: PlotCurve.cpp:170
TitleType getTitleType() const
void setBroker(MessageBroker *broker)
Definition: PlotCurve.cpp:109
void stateChanged(int state)
PlotLegendConfig * getLegendConfig() const
Definition: PlotConfig.cpp:83
void setState(State state)
Definition: PlotWidget.cpp:311
void setBroker(MessageBroker *broker)
Definition: PlotWidget.cpp:252
PlotConfig * getConfig() const
Definition: PlotWidget.cpp:248
void dropEvent(QDropEvent *event)
Definition: PlotWidget.cpp:520
PlotMagnifier * magnifier_
Definition: PlotWidget.h:120
PlotAxisConfig * getAxisConfig(Axis axis) const
BoundingRectangle getPreferredScale() const
Definition: PlotWidget.cpp:269
void configCurveConfigChanged(size_t index)
Definition: PlotWidget.cpp:651
PlotWidget(QWidget *parent=0)
Definition: PlotWidget.cpp:57
void saveToImageFile(const QString &fileName)
Definition: PlotWidget.cpp:464
bool canChangeState() const
Definition: PlotWidget.cpp:332
const BoundingRectangle & getCurrentScale() const
Definition: PlotWidget.cpp:299
BoundingRectangle currentBounds_
Definition: PlotWidget.h:128
void configCurveAdded(size_t index)
Definition: PlotWidget.cpp:605
const QString & getTitle() const
Definition: PlotConfig.cpp:56
const QString & getField() const
void writeFormattedCurveAxisTitles(QStringList &formattedAxisTitles)
Definition: PlotWidget.cpp:436
void configTitleChanged(const QString &title)
Definition: PlotWidget.cpp:601
void setCanChangeState(bool can)
Definition: PlotWidget.cpp:328
double getPlotRate() const
Definition: PlotConfig.cpp:96
void preferredScaleChanged(const BoundingRectangle &bounds)
void writeFormattedCurveData(QList< QStringList > &formattedData)
Definition: PlotWidget.cpp:423
ROSLIB_DECL std::string getPath(const std::string &package_name)
CurveConfig * getCurveConfig(size_t index) const
Definition: PlotConfig.cpp:72
void dragEnterEvent(QDragEnterEvent *event)
Definition: PlotWidget.cpp:512
PlotCursor * getCursor() const
Definition: PlotWidget.cpp:265
size_t getNumCurves() const
Definition: PlotConfig.cpp:68
void setTitle(const QString &title)
Definition: PlotConfig.cpp:47
void renderToPixmap(QPixmap &pixmap, const QRectF &bounds=QRectF())
Definition: PlotWidget.cpp:395
void currentScaleChanged(const BoundingRectangle &bounds)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
void setTitle(const QString &title)
Definition: CurveConfig.cpp:60
void saveToTextFile(const QString &fileName)
Definition: PlotWidget.cpp:473
void setConfig(PlotConfig *config)
Definition: PlotWidget.cpp:189
void configPlotRateChanged(double rate)
Definition: PlotWidget.cpp:675
void setConfig(CurveConfig *config)
Definition: PlotCurve.cpp:56
MessageBroker * broker_
Definition: PlotWidget.h:113
void configCurveRemoved(size_t index)
Definition: PlotWidget.cpp:623
Ui::PlotWidget * ui_
Definition: PlotWidget.h:102
void updateAxisTitle(PlotAxesConfig::Axis axis)
Definition: PlotWidget.cpp:555
bool isReplotRequested() const
Definition: PlotWidget.cpp:307


rqt_multiplot_plugin
Author(s): Ralf Kaestner
autogenerated on Fri Jan 15 2021 03:47:53