23 #include <qtconcurrentrun.h> 25 #if !defined(QT_NO_QFUTURE) 26 #define QWT_USE_THREADS 1 33 return qRound( value );
40 return ( value >= 0.0 ) ? std::floor( value + 0.5 ) : std::ceil( value - 0.5 );
42 return nearbyint( value );
52 return Qt::Horizontal;
55 const double x0 = series->
sample( from ).x();
56 const double xn = series->
sample( to ).x();
61 const int step = ( to - from ) / 10;
62 const bool isIncreasing = xn > x0;
65 for (
int i = from + step; i < to; i += step )
67 const double x2 = series->
sample( i ).x();
70 if ( ( x2 > x1 ) != isIncreasing )
77 return Qt::Horizontal;
82 template <
class Polygon,
class Po
int>
83 class QwtPolygonQuadrupelX
86 inline void start(
int x,
int y )
89 y1 = yMin = yMax = y2 = y;
92 inline bool append(
int x,
int y )
107 inline void flush( Polygon &polyline )
109 appendTo( y1, polyline );
115 appendTo( yMax, polyline );
118 appendTo( yMin, polyline );
121 appendTo( y2, polyline );
125 inline void appendTo(
int y, Polygon &polyline )
127 polyline += Point( x0, y );
131 int x0, y1, yMin, yMax, y2;
134 template <
class Polygon,
class Po
int>
135 class QwtPolygonQuadrupelY
138 inline void start(
int x,
int y )
141 x1 = xMin = xMax = x2 = x;
144 inline bool append(
int x,
int y )
159 inline void flush( Polygon &polyline )
161 appendTo( x1, polyline );
167 appendTo( xMax, polyline );
170 appendTo( xMin, polyline );
173 appendTo( x2, polyline );
177 inline void appendTo(
int x, Polygon &polyline )
179 polyline += Point( x, y0 );
182 int y0, x1, xMin, xMax, x2;
186 template <
class Polygon,
class Po
int,
class PolygonQuadrupel>
190 const QPointF sample0 = series->
sample( from );
197 for (
int i = from; i <= to; i++ )
199 const QPointF sample = series->
sample( i );
204 if ( !q.append( x, y ) )
215 template <
class Polygon,
class Po
int,
class PolygonQuadrupel>
218 const int numPoints = polyline.size();
223 const Point *points = polyline.constData();
228 q.start( points[0].x(), points[0].y() );
230 for (
int i = 0; i < numPoints; i++ )
232 const int x = points[i].x();
233 const int y = points[i].y();
235 if ( !q.append( x, y ) )
237 q.flush( polylineXY );
241 q.flush( polylineXY );
247 template <
class Polygon,
class Po
int>
261 if ( orientation == Qt::Horizontal )
264 QwtPolygonQuadrupelY<Polygon, Point> >( xMap, yMap, series, from, to );
267 QwtPolygonQuadrupelX<Polygon, Point> >( polyline );
272 QwtPolygonQuadrupelX<Polygon, Point> >( xMap, yMap, series, from, to );
275 QwtPolygonQuadrupelY<Polygon, Point> >( polyline );
296 const QRgb rgb = command.
rgb;
297 QRgb *bits =
reinterpret_cast<QRgb *
>( image->bits() );
299 const int w = image->width();
300 const int h = image->height();
302 const int x0 = pos.x();
303 const int y0 = pos.y();
305 for (
int i = command.
from; i <= command.
to; i++ )
309 const int x =
static_cast<int>( xMap.
transform( sample.x() ) + 0.5 ) - x0;
310 const int y =
static_cast<int>( yMap.
transform( sample.y() ) + 0.5 ) - y0;
312 if ( x >= 0 && x < w && y >= 0 && y < h )
313 bits[ y * w + x ] = rgb;
345 template<
class Polygon,
class Po
int,
class Round>
347 const QRectF &boundingRect,
350 int from,
int to, Round round )
352 Polygon polyline( to - from + 1 );
353 Point *points = polyline.data();
357 if ( boundingRect.isValid() )
363 for (
int i = from; i <= to; i++ )
365 const QPointF sample = series->
sample( i );
367 const double x = xMap.
transform( sample.x() );
368 const double y = yMap.
transform( sample.y() );
370 if ( boundingRect.contains( x, y ) )
372 points[ numPoints ].rx() = round( x );
373 points[ numPoints ].ry() = round( y );
379 polyline.resize( numPoints );
386 for (
int i = from; i <= to; i++ )
388 const QPointF sample = series->
sample( i );
390 const double x = xMap.
transform( sample.x() );
391 const double y = yMap.
transform( sample.y() );
393 points[ numPoints ].rx() = round( x );
394 points[ numPoints ].ry() = round( y );
404 const QRectF &boundingRect,
409 return qwtToPoints<QPolygon, QPoint>(
410 boundingRect, xMap, yMap, series, from, to,
QwtRoundI() );
413 template<
class Round>
415 const QRectF &boundingRect,
418 int from,
int to, Round round )
420 return qwtToPoints<QPolygonF, QPointF>(
421 boundingRect, xMap, yMap, series, from, to, round );
427 template<
class Polygon,
class Po
int,
class Round>
431 int from,
int to, Round round )
438 Polygon polyline( to - from + 1 );
439 Point *points = polyline.data();
441 const QPointF sample0 = series->
sample( from );
443 points[0].rx() = round( xMap.
transform( sample0.x() ) );
444 points[0].ry() = round( yMap.
transform( sample0.y() ) );
447 for (
int i = from + 1; i <= to; i++ )
449 const QPointF sample = series->
sample( i );
451 const Point p( round( xMap.
transform( sample.x() ) ),
454 if ( points[pos] != p )
458 polyline.resize( pos + 1 );
467 return qwtToPolylineFiltered<QPolygon, QPoint>(
468 xMap, yMap, series, from, to,
QwtRoundI() );
471 template<
class Round>
475 int from,
int to, Round round )
477 return qwtToPolylineFiltered<QPolygonF, QPointF>(
478 xMap, yMap, series, from, to, round );
481 template<
class Polygon,
class Po
int>
483 const QRectF &boundingRect,
490 Polygon polygon( to - from + 1 );
491 Point *points = polygon.data();
496 for (
int i = from; i <= to; i++ )
498 const QPointF sample = series->
sample( i );
503 if ( pixelMatrix.testAndSetPixel( x, y,
true ) == false )
505 points[ numPoints ].rx() = x;
506 points[ numPoints ].ry() = y;
512 polygon.resize( numPoints );
517 const QRectF &boundingRect,
521 return qwtToPointsFiltered<QPolygon, QPoint>(
522 boundingRect, xMap, yMap, series, from, to );
526 const QRectF &boundingRect,
530 return qwtToPointsFiltered<QPolygonF, QPointF>(
531 boundingRect, xMap, yMap, series, from, to );
566 d_data->flags = flags;
575 return d_data->flags;
589 d_data->flags |= flag;
591 d_data->flags &= ~flag;
601 return d_data->flags & flag;
614 d_data->boundingRect = rect;
623 return d_data->boundingRect;
653 if ( d_data->flags & RoundPoints )
655 if ( d_data->flags & WeedOutIntermediatePoints )
657 polyline = qwtMapPointsQuad<QPolygonF, QPointF>(
658 xMap, yMap, series, from, to );
660 else if ( d_data->flags & WeedOutPoints )
663 xMap, yMap, series, from, to,
QwtRoundF() );
668 xMap, yMap, series, from, to,
QwtRoundF() );
673 if ( d_data->flags & WeedOutPoints )
708 if ( d_data->flags & WeedOutIntermediatePoints )
711 polyline = qwtMapPointsQuad<QPolygon, QPoint>(
712 xMap, yMap, series, from, to );
714 else if ( d_data->flags & WeedOutPoints )
717 xMap, yMap, series, from, to );
765 if ( d_data->flags & WeedOutPoints )
767 if ( d_data->flags & RoundPoints )
769 if ( d_data->boundingRect.isValid() )
772 xMap, yMap, series, from, to );
781 xMap, yMap, series, from, to,
QwtRoundF() );
795 if ( d_data->flags & RoundPoints )
798 xMap, yMap, series, from, to,
QwtRoundF() );
839 if ( d_data->flags & WeedOutPoints )
841 if ( d_data->boundingRect.isValid() )
844 xMap, yMap, series, from, to );
852 xMap, yMap, series, from, to );
858 d_data->boundingRect, xMap, yMap, series, from, to );
886 const QPen &pen,
bool antialiased, uint numThreads )
const 888 Q_UNUSED( antialiased )
891 if ( numThreads == 0 )
892 numThreads = QThread::idealThreadCount();
894 if ( numThreads <= 0 )
897 Q_UNUSED( numThreads )
903 const QRect rect = d_data->boundingRect.toAlignedRect();
905 QImage image( rect.size(), QImage::Format_ARGB32 );
906 image.fill( Qt::transparent );
908 if ( pen.width() <= 1 && pen.color().alpha() == 255 )
912 command.
rgb = pen.color().rgba();
915 const int numPoints = ( to - from + 1 ) / numThreads;
918 for ( uint i = 0; i < numThreads; i++ )
920 const QPoint pos = rect.topLeft();
922 const int index0 = from + i * numPoints;
923 if ( i == numThreads - 1 )
925 command.
from = index0;
932 command.
from = index0;
933 command.
to = index0 + numPoints - 1;
936 xMap, yMap, command, pos, &image );
939 for (
int i = 0; i < futures.size(); i++ )
940 futures[i].waitForFinished();
945 qwtRenderDots( xMap, yMap, command, rect.topLeft(), &image );
953 QPainter painter( &image );
954 painter.setPen( pen );
955 painter.setRenderHint( QPainter::Antialiasing, antialiased );
957 const int chunkSize = 1000;
958 for (
int i = from; i <= to; i += chunkSize )
960 const int indexTo = qMin( i + chunkSize - 1, to );
961 const QPolygon points = toPoints(
962 xMap, yMap, series, i, indexTo );
964 painter.drawPoints( points );
QRectF boundingRect() const
void setFlags(TransformationFlags)
QFlags< TransformationFlag > TransformationFlags
Flags affecting the transformation process.
enum MQTTPropertyCodes value
QPolygonF toPointsF(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to) const
Translate a series into a QPolygonF.
A bit field corresponding to the pixels of a rectangle.
void setBoundingRect(const QRectF &)
int operator()(double value) const
QwtPointMapper()
Constructor.
TransformationFlag
Flags affecting the transformation process.
static QPolygon qwtToPointsI(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
static void qwtRenderDots(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtDotsCommand &command, const QPoint &pos, QImage *image)
QPolygon toPolygon(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to) const
Translate a series of points into a QPolygon.
static QRectF qwtInvalidRect(0.0, 0.0,-1.0,-1.0)
bool testFlag(TransformationFlag) const
void setFlag(TransformationFlag, bool on=true)
static Polygon qwtMapPointsQuad(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
static QPolygon qwtToPolylineFilteredI(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
QPolygon toPoints(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to) const
Translate a series of points into a QPolygon.
static QPolygonF qwtToPolylineFilteredF(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to, Round round)
ROSLIB_DECL std::string command(const std::string &cmd)
~QwtPointMapper()
Destructor.
double operator()(double value) const
static QPolygonF qwtToPointsFilteredF(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
static int qwtRoundValue(double value)
static Polygon qwtToPoints(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to, Round round)
const QwtSeriesData< QPointF > * series
QPolygonF toPolygonF(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to) const
Translate a series of points into a QPolygonF.
double operator()(double value) const
static Polygon qwtToPointsFiltered(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
virtual T sample(size_t i) const =0
static QPolygonF qwtToPointsF(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to, Round round)
QImage toImage(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to, const QPen &, bool antialiased, uint numThreads) const
Translate a series into a QImage.
static Polygon qwtToPolylineFiltered(const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to, Round round)
double transform(double s) const
static double qwtRoundValueF(double value)
QwtPointMapper::TransformationFlags flags
static Qt::Orientation qwtProbeOrientation(const QwtSeriesData< QPointF > *series, int from, int to)
static QPolygon qwtToPointsFilteredI(const QRectF &boundingRect, const QwtScaleMap &xMap, const QwtScaleMap &yMap, const QwtSeriesData< QPointF > *series, int from, int to)
TransformationFlags flags() const