CurveDataCircularBuffer.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 
00021 namespace rqt_multiplot {
00022 
00023 /*****************************************************************************/
00024 /* Constructors and Destructor                                               */
00025 /*****************************************************************************/
00026 
00027 CurveDataCircularBuffer::CurveDataCircularBuffer(size_t capacity) :
00028   points_(capacity) {
00029   xMin_.reserve(capacity);
00030   xMax_.reserve(capacity);
00031   yMin_.reserve(capacity);
00032   yMax_.reserve(capacity);
00033 }
00034 
00035 CurveDataCircularBuffer::~CurveDataCircularBuffer() {
00036 }
00037 
00038 /*****************************************************************************/
00039 /* Accessors                                                                 */
00040 /*****************************************************************************/
00041 
00042 size_t CurveDataCircularBuffer::getCapacity() const {
00043   return points_.capacity();
00044 }
00045 
00046 size_t CurveDataCircularBuffer::getNumPoints() const {
00047   return points_.size();
00048 }
00049 
00050 QPointF CurveDataCircularBuffer::getPoint(size_t index) const {
00051   const Point& point = points_[index];
00052   
00053   return QPointF(point.x_, point.y_);
00054 }
00055 
00056 QVector<size_t> CurveDataCircularBuffer::getPointsInDistance(double x,
00057     double maxDistance) const {
00058   QVector<size_t> indexes;
00059       
00060   XCoordinateRefMinHeap::ordered_iterator it = std::lower_bound(
00061     xMin_.ordered_begin(), xMin_.ordered_end(), x-maxDistance);
00062   
00063   while (it != xMin_.ordered_end()) {
00064     if (fabs(x-it->x_) <= maxDistance) {
00065       size_t index = it->index_;
00066       
00067       if (points_.array_two().second) {
00068         index = (index < points_.array_two().second) ?
00069           index+points_.array_one().second :
00070           index-points_.array_two().second;
00071       }
00072       
00073       indexes.push_back(index);
00074       ++it;
00075     }
00076     else
00077       break;
00078   }
00079   
00080   return indexes;
00081 }
00082 
00083 BoundingRectangle CurveDataCircularBuffer::getBounds() const {
00084   if (!points_.empty()) {
00085     QPointF minimum(xMin_.top().x_, yMin_.top());
00086     QPointF maximum(xMax_.top(), yMax_.top());
00087     
00088     return BoundingRectangle(minimum, maximum);
00089   }
00090   
00091   
00092   return BoundingRectangle();
00093 }
00094 
00095 /*****************************************************************************/
00096 /* Methods                                                                   */
00097 /*****************************************************************************/
00098 
00099 void CurveDataCircularBuffer::appendPoint(const QPointF& point) {
00100   if (points_.full()) {
00101     const Point& firstPoint = points_[0];
00102     
00103     xMin_.erase(firstPoint.xMinHandle_);
00104     xMax_.erase(firstPoint.xMaxHandle_);
00105     yMin_.erase(firstPoint.yMinHandle_);
00106     yMax_.erase(firstPoint.yMaxHandle_);
00107   }
00108   
00109   points_.push_back(point);
00110   size_t index = points_.size()-1;
00111 
00112   if (points_.array_two().second)
00113     index = (points_.array_one().first < points_.array_two().first) ?
00114       &points_.back()-points_.array_one().first :
00115       &points_.back()-points_.array_two().first;
00116   
00117   points_.back().xMinHandle_ = xMin_.push(XCoordinateRef(point.x(), index));
00118   points_.back().xMaxHandle_ = xMax_.push(point.x());
00119   points_.back().yMinHandle_ = yMin_.push(point.y());
00120   points_.back().yMaxHandle_ = yMax_.push(point.y());  
00121 }
00122 
00123 void CurveDataCircularBuffer::clearPoints() {
00124   points_.clear();
00125   
00126   xMin_.clear();
00127   xMax_.clear();
00128   yMin_.clear();
00129   yMax_.clear();
00130 }
00131 
00132 }


rqt_multiplot
Author(s): Ralf Kaestner
autogenerated on Thu Jun 6 2019 21:49:10