PlotCurve.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Copyright (C) 2015 by Ralf Kaestner                                        *
00003  * ralf.kaestner@gmail.com                                                    *
00004  *                                                                            *
00005  * This program is free software; you can redistribute it and/or modify       *
00006  * it under the terms of the Lesser GNU General Public License as published by*
00007  * the Free Software Foundation; either version 3 of the License, or          *
00008  * (at your option) any later version.                                        *
00009  *                                                                            *
00010  * This program is distributed in the hope that it will be useful,            *
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of             *
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the               *
00013  * Lesser GNU General Public License for more details.                        *
00014  *                                                                            *
00015  * You should have received a copy of the Lesser GNU General Public License   *
00016  * along with this program. If not, see <http://www.gnu.org/licenses/>.       *
00017  ******************************************************************************/
00018 
00019 #include <rqt_multiplot/CurveDataCircularBuffer.h>
00020 #include <rqt_multiplot/CurveDataList.h>
00021 #include <rqt_multiplot/CurveDataListTimeFrame.h>
00022 #include <rqt_multiplot/CurveDataSequencer.h>
00023 #include <rqt_multiplot/CurveDataVector.h>
00024 #include <rqt_multiplot/PlotWidget.h>
00025 
00026 #include "rqt_multiplot/PlotCurve.h"
00027 
00028 namespace rqt_multiplot {
00029 
00030 /*****************************************************************************/
00031 /* Constructors and Destructor                                               */
00032 /*****************************************************************************/
00033 
00034 PlotCurve::PlotCurve(QObject* parent) :
00035   QObject(parent),
00036   config_(0),
00037   broker_(0),
00038   data_(new CurveDataVector()),
00039   dataSequencer_(new CurveDataSequencer(this)),
00040   paused_(true) {
00041   qRegisterMetaType<BoundingRectangle>("BoundingRectangle");
00042   
00043   connect(dataSequencer_, SIGNAL(pointReceived(const QPointF&)), 
00044     this, SLOT(dataSequencerPointReceived(const QPointF&)));
00045   
00046   setData(data_);
00047 }
00048 
00049 PlotCurve::~PlotCurve() {
00050 }
00051 
00052 /*****************************************************************************/
00053 /* Accessors                                                                 */
00054 /*****************************************************************************/
00055 
00056 void PlotCurve::setConfig(CurveConfig* config) {
00057   if (config != config_) {
00058     if (config_) {
00059       disconnect(config_, SIGNAL(changed(const QString&)), this,
00060         SLOT(configTitleChanged(const QString&)));
00061       disconnect(config_->getAxisConfig(CurveConfig::X),
00062         SIGNAL(changed()), this, SLOT(configAxisConfigChanged()));
00063       disconnect(config_->getAxisConfig(CurveConfig::Y),
00064         SIGNAL(changed()), this, SLOT(configAxisConfigChanged()));
00065       disconnect(config_->getColorConfig(), SIGNAL(currentColorChanged(
00066         const QColor&)), this, SLOT(configColorConfigCurrentColorChanged(
00067         const QColor&)));
00068       disconnect(config_->getStyleConfig(), SIGNAL(changed()), this,
00069         SLOT(configStyleConfigChanged()));
00070       disconnect(config_->getDataConfig(), SIGNAL(changed()), this,
00071         SLOT(configDataConfigChanged()));
00072       
00073       dataSequencer_->setConfig(0);
00074     }
00075     
00076     config_ = config;
00077     
00078     if (config) {
00079       connect(config, SIGNAL(titleChanged(const QString&)), this,
00080         SLOT(configTitleChanged(const QString&)));
00081       connect(config->getAxisConfig(CurveConfig::X),
00082         SIGNAL(changed()), this, SLOT(configAxisConfigChanged()));
00083       connect(config->getAxisConfig(CurveConfig::Y),
00084         SIGNAL(changed()), this, SLOT(configAxisConfigChanged()));
00085       connect(config->getColorConfig(), SIGNAL(currentColorChanged(
00086         const QColor&)), this, SLOT(configColorConfigCurrentColorChanged(
00087         const QColor&)));
00088       connect(config->getStyleConfig(), SIGNAL(changed()), this,
00089         SLOT(configStyleConfigChanged()));
00090       connect(config->getDataConfig(), SIGNAL(changed()), this,
00091         SLOT(configDataConfigChanged()));
00092       
00093       configTitleChanged(config->getTitle());
00094       configAxisConfigChanged();
00095       configColorConfigCurrentColorChanged(config->getColorConfig()->
00096         getCurrentColor());
00097       configStyleConfigChanged();
00098       configDataConfigChanged();
00099       
00100       dataSequencer_->setConfig(config);
00101     }
00102   }
00103 }
00104 
00105 CurveConfig* PlotCurve::getConfig() const {
00106   return config_;
00107 }
00108 
00109 void PlotCurve::setBroker(MessageBroker* broker) {
00110   if (broker != broker_) {
00111     broker_ = broker;
00112     
00113     dataSequencer_->setBroker(broker);
00114   }
00115 }
00116 
00117 MessageBroker* PlotCurve::getBroker() const {
00118   return broker_;
00119 }
00120 
00121 CurveData* PlotCurve::getData() const {
00122   return data_;
00123 }
00124 
00125 CurveDataSequencer* PlotCurve::getDataSequencer() const {
00126   return dataSequencer_;
00127 }
00128 
00129 QPair<double, double> PlotCurve::getPreferredAxisScale(CurveConfig::Axis axis)
00130     const {
00131   QPair<double, double> axisBounds(0.0, -1.0);
00132   
00133   if (config_) {
00134     CurveAxisScaleConfig* axisScaleConfig = config_->getAxisConfig(axis)->
00135       getScaleConfig();
00136     
00137     if (axisScaleConfig->getType() == CurveAxisScaleConfig::Absolute) {
00138       axisBounds.first = axisScaleConfig->getAbsoluteMinimum();
00139       axisBounds.second = axisScaleConfig->getAbsoluteMaximum();
00140     }
00141     else if (axisScaleConfig->getType() == CurveAxisScaleConfig::Relative) {
00142       if (!data_->isEmpty()) {
00143         size_t index = data_->getNumPoints()-1;
00144         
00145         axisBounds.first = data_->getValue(index, axis)+axisScaleConfig->
00146           getRelativeMinimum();
00147         axisBounds.second = data_->getValue(index, axis)+axisScaleConfig->
00148           getRelativeMaximum();
00149       }
00150     }
00151     else
00152       axisBounds = data_->getAxisBounds(axis);
00153   }
00154   
00155   return axisBounds;
00156 }
00157 
00158 BoundingRectangle PlotCurve::getPreferredScale() const {
00159   QPair<double, double> xAxisBounds = getPreferredAxisScale(CurveConfig::X);
00160   QPair<double, double> yAxisBounds = getPreferredAxisScale(CurveConfig::Y);
00161 
00162   return BoundingRectangle(QPointF(xAxisBounds.first, yAxisBounds.first),
00163     QPointF(xAxisBounds.second, yAxisBounds.second));
00164 }
00165 
00166 /*****************************************************************************/
00167 /* Methods                                                                   */
00168 /*****************************************************************************/
00169 
00170 void PlotCurve::attach(QwtPlot* plot) {
00171   QwtPlotCurve::attach(plot);
00172 }
00173 
00174 void PlotCurve::detach() {
00175   QwtPlotCurve::detach();
00176 }
00177 
00178 void PlotCurve::run() {
00179   CurveAxisConfig* xAxisConfig = config_->getAxisConfig(CurveConfig::X);
00180   CurveAxisConfig* yAxisConfig = config_->getAxisConfig(CurveConfig::Y);
00181 
00182   if (paused_ &&
00183       (!xAxisConfig->getField().isEmpty() ||
00184           xAxisConfig->getFieldType() == CurveAxisConfig::MessageReceiptTime) &&
00185       (!yAxisConfig->getField().isEmpty() ||
00186           yAxisConfig->getFieldType() == CurveAxisConfig::MessageReceiptTime)) {
00187     dataSequencer_->subscribe();
00188 
00189     paused_ = false;
00190   }
00191 }
00192 
00193 void PlotCurve::pause() {
00194   if (!paused_) {
00195     dataSequencer_->unsubscribe();
00196 
00197     paused_ = true;
00198   }
00199 }
00200 
00201 void PlotCurve::clear() {
00202   data_->clearPoints();
00203   
00204   emit replotRequested();
00205 }
00206 
00207 /*****************************************************************************/
00208 /* Slots                                                                     */
00209 /*****************************************************************************/
00210 
00211 void PlotCurve::configTitleChanged(const QString& title) {
00212   setTitle(title);
00213 }
00214 
00215 void PlotCurve::configAxisConfigChanged() {
00216   emit preferredScaleChanged(getPreferredScale());
00217 }
00218 
00219 void PlotCurve::configColorConfigCurrentColorChanged(const QColor& color) {
00220   setPen(color);
00221   
00222   emit replotRequested();
00223 }
00224 
00225 void PlotCurve::configStyleConfigChanged() {
00226   rqt_multiplot::CurveStyleConfig* styleConfig = config_->getStyleConfig();
00227   
00228   if (styleConfig->getType() == rqt_multiplot::CurveStyleConfig::Sticks) {
00229     setStyle(QwtPlotCurve::Sticks);
00230     
00231     setOrientation(styleConfig->getSticksOrientation());
00232     setBaseline(styleConfig->getSticksBaseline());
00233   }
00234   else if (styleConfig->getType() == rqt_multiplot::CurveStyleConfig::
00235       Steps) {
00236     setStyle(QwtPlotCurve::Steps);
00237     
00238     setCurveAttribute(QwtPlotCurve::Inverted, styleConfig->
00239       areStepsInverted());    
00240   }
00241   else if (styleConfig->getType() == rqt_multiplot::CurveStyleConfig::
00242       Points) {
00243     setStyle(QwtPlotCurve::Dots);
00244   }
00245   else {
00246     setStyle(QwtPlotCurve::Lines);
00247     
00248     setCurveAttribute(QwtPlotCurve::Fitted, styleConfig->
00249       areLinesInterpolated());    
00250   }
00251   
00252   QPen pen = QwtPlotCurve::pen();
00253 
00254   pen.setWidth(styleConfig->getPenWidth());
00255   pen.setStyle(styleConfig->getPenStyle());
00256   
00257   setPen(pen);
00258   
00259   setRenderHint(QwtPlotItem::RenderAntialiased, styleConfig->
00260     isRenderAntialiased());
00261   
00262   emit replotRequested();
00263 }
00264 
00265 void PlotCurve::configDataConfigChanged() {
00266   CurveDataConfig* config = config_->getDataConfig();
00267 
00268   if (config->getType() == CurveDataConfig::List)
00269     data_ = new CurveDataList();
00270   if (config->getType() == CurveDataConfig::CircularBuffer)
00271     data_ = new CurveDataCircularBuffer(config->getCircularBufferCapacity());
00272   if (config->getType() == CurveDataConfig::TimeFrame)
00273     data_ = new CurveDataListTimeFrame(config->getTimeFrameLength());
00274   else
00275     data_ = new CurveDataVector();
00276   
00277   setData(data_);
00278   
00279   emit replotRequested();
00280 }
00281 
00282 void PlotCurve::dataSequencerPointReceived(const QPointF& point) {
00283   if (!paused_) {
00284     BoundingRectangle oldBounds = getPreferredScale();
00285     
00286     data_->appendPoint(point);
00287     
00288     BoundingRectangle bounds = getPreferredScale();
00289     
00290     if (bounds != oldBounds)
00291       emit preferredScaleChanged(bounds);
00292 
00293     emit replotRequested();
00294   }
00295 }
00296 
00297 }


rqt_multiplot
Author(s): Ralf Kaestner
autogenerated on Tue May 9 2017 02:16:02