qparticleviewer.h
Go to the documentation of this file.
00001 /*****************************************************************
00002  *
00003  * This file is part of the GMAPPING project
00004  *
00005  * GMAPPING Copyright (c) 2004 Giorgio Grisetti, 
00006  * Cyrill Stachniss, and Wolfram Burgard
00007  *
00008  * This software is licensed under the "Creative Commons 
00009  * License (Attribution-NonCommercial-ShareAlike 2.0)" 
00010  * and is copyrighted by Giorgio Grisetti, Cyrill Stachniss, 
00011  * and Wolfram Burgard.
00012  * 
00013  * Further information on this license can be found at:
00014  * http://creativecommons.org/licenses/by-nc-sa/2.0/
00015  * 
00016  * GMAPPING is distributed in the hope that it will be useful,
00017  * but WITHOUT ANY WARRANTY; without even the implied 
00018  * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
00019  * PURPOSE.  
00020  *
00021  *****************************************************************/
00022 
00023 
00024 #ifndef QPARTICLEVIEWER_H
00025 #define QPARTICLEVIEWER_H
00026 
00027 #include <qpainter.h>
00028 #include <qpixmap.h>
00029 #include <qwidget.h>
00030 #include <qwmatrix.h>
00031 #include <qtextstream.h>
00032 #include <vector>
00033 #include <assert.h>
00034 #include <sstream>
00035 #include <iostream>
00036 #include <qimage.h>
00037 
00038 #include <utils/point.h>
00039 #include "gsp_thread.h"
00040 
00041 namespace GMapping {
00042 
00043 class QParticleViewer :  public QWidget{
00044         Q_OBJECT
00045         public:
00046                 struct StartParameters{
00047                         //motionmodel
00048                         double srr, srt, str, stt;
00049                         //map
00050                         double xmin, ymin, xmax, ymax, delta;
00051                         OrientedPoint initialPose;
00052                         //likelihood
00053                         double lsigma, lgain;
00054                         unsigned int lskip;
00055                         //update
00056                         double linearUpdate, angularUpdate;
00057                         //filter
00058                         unsigned int particles;
00059                         double resampleThreshold;
00060                         //mode
00061                         bool drawFromObservation;
00062                         //output
00063                         const char * outFileName;
00064                 };
00065                 
00066                 struct MatchingParameters{
00067                         //ranges
00068                         double maxrange, urange;
00069                         //score
00070                         double ssigma, sreg, scrit;
00071                         unsigned int ksize;
00072                         //search
00073                         double lstep, astep;
00074                         unsigned int iterations;
00075                 };
00076 
00077                 void refreshParameters(); //reads the parameters from the thread
00078                 inline void setGSP( GridSlamProcessorThread* thread){gfs_thread=thread;}
00079                 
00080                 
00081                 typedef std::vector<OrientedPoint> OrientedPointVector;
00082                 QParticleViewer( QWidget * parent = 0, const char * name = 0, WFlags f = 0, GridSlamProcessorThread* thread=0 );
00083                 virtual ~QParticleViewer();
00084                 virtual void timerEvent(QTimerEvent * te);
00085                 virtual void resizeEvent(QResizeEvent *);
00086                 
00087                 void drawFromFile();
00088                 void drawFromMemory();
00089                 void drawMap(const ScanMatcherMap& map);
00090                 void start(int period);
00091                 QTextIStream* tis;
00092                 
00093                 MatchingParameters matchingParameters;
00094                 StartParameters startParameters;
00095                 
00096                 int writeToFile;
00097         public slots:
00098                 void setMatchingParameters(const MatchingParameters& mp);
00099                 void setStartParameters(const StartParameters& mp);
00100                 void start();
00101                 void stop();
00102                 void loadFile(const char *);
00103         signals:
00104                 void neffChanged(double);
00105                 void poseEntropyChanged(double, double, double);
00106                 void trajectoryEntropyChanged(double, double, double);
00107                 void mapsEntropyChanged(double);
00108                 void mapsIGainChanged(double);
00109                 
00110         protected:
00111                 ifstream inputStream;
00112                 ofstream outputStream;
00113                 
00114                         
00115         protected:
00116                 inline Point pic2map(const IntPoint& p) 
00117                         {return viewCenter+Point(p.x/mapscale, -p.y/mapscale); }
00118                 inline IntPoint map2pic(const Point& p)
00119                         {return IntPoint((int)((p.x-viewCenter.x)*mapscale),(int)((viewCenter.y-p.y)*mapscale)); }
00120                 
00121                 int timer;
00122                 virtual void paintEvent ( QPaintEvent *paintevent );
00123                 void drawParticleMove(const OrientedPointVector& start, const OrientedPointVector& end); 
00124                 QPixmap* m_pixmap;
00125                 
00126                 //thread interaction
00127                 GridSlamProcessorThread* gfs_thread;
00128                 GridSlamProcessorThread::EventDeque history;
00129                 
00130                 //mouse movement
00131                 virtual void mousePressEvent(QMouseEvent*);
00132                 virtual void mouseReleaseEvent(QMouseEvent*);
00133                 virtual void mouseMoveEvent(QMouseEvent*);
00134                 QPoint draggingPos;
00135                 bool dragging;
00136                 
00137                 //particle plotting
00138                 virtual void keyPressEvent ( QKeyEvent* e );
00139                 
00140                 //map painting
00141                 double mapscale;
00142                 Point viewCenter;
00143                 Point bestParticlePose;
00144                 ScanMatcherMap * bestMap;
00145                 
00146                 // view mode
00147                 bool showPaths;
00148                 bool showBestPath;
00149                 
00150                 // file plotting
00151                 QParticleViewer::OrientedPointVector m_oldPose, m_newPose;
00152                 unsigned int m_particleSize;
00153                 bool m_refresh;
00154                 int count;
00155 };
00156 
00157 };
00158 
00159 #endif
00160 


openslam_gmapping
Author(s): Giorgio Grisetti, Cyrill Stachniss, Wolfram Burgard
autogenerated on Fri Aug 28 2015 11:56:21