GraphViewer.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef GRAPHVIEWER_H_
00029 #define GRAPHVIEWER_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include <QGraphicsView>
00034 #include <QtCore/QMap>
00035 #include <QtCore/QSettings>
00036 #include <rtabmap/core/Link.h>
00037 #include <opencv2/opencv.hpp>
00038 #include <map>
00039 
00040 class QGraphicsItem;
00041 class QGraphicsPixmapItem;
00042 class QGraphicsItemGroup;
00043 
00044 namespace rtabmap {
00045 
00046 class NodeItem;
00047 class LinkItem;
00048 
00049 class RTABMAPGUI_EXP GraphViewer : public QGraphicsView {
00050 
00051         Q_OBJECT;
00052 
00053 public:
00054         GraphViewer(QWidget * parent = 0);
00055         virtual ~GraphViewer();
00056 
00057         void updateGraph(const std::map<int, Transform> & poses,
00058                                          const std::multimap<int, Link> & constraints,
00059                                          const std::map<int, int> & mapIds);
00060         void updateGTGraph(const std::map<int, Transform> & poses);
00061         void updateReferentialPosition(const Transform & t);
00062         void updateMap(const cv::Mat & map8U, float resolution, float xMin, float yMin);
00063         void updatePosterior(const std::map<int, float> & posterior);
00064         void updateLocalPath(const std::vector<int> & localPath);
00065         void setGlobalPath(const std::vector<std::pair<int, Transform> > & globalPath);
00066         void setCurrentGoalID(int id, const Transform & pose = Transform());
00067         void setLocalRadius(float radius);
00068         void clearGraph();
00069         void clearMap();
00070         void clearPosterior();
00071         void clearAll();
00072 
00073         void saveSettings(QSettings & settings, const QString & group = "") const;
00074         void loadSettings(QSettings & settings, const QString & group = "");
00075 
00076         //getters
00077         const QString & getWorkingDirectory() const {return _workingDirectory;}
00078         float getNodeRadius() const {return _nodeRadius;}
00079         float getLinkWidth() const {return _linkWidth;}
00080         const QColor & getNodeColor() const {return _nodeColor;}
00081         const QColor & getCurrentGoalColor() const {return _currentGoalColor;}
00082         const QColor & getNeighborColor() const {return _neighborColor;}
00083         const QColor & getGlobalLoopClosureColor() const {return _loopClosureColor;}
00084         const QColor & getLocalLoopClosureColor() const {return _loopClosureLocalColor;}
00085         const QColor & getUserLoopClosureColor() const {return _loopClosureUserColor;}
00086         const QColor & getVirtualLoopClosureColor() const {return _loopClosureVirtualColor;}
00087         const QColor & getNeighborMergedColor() const {return _neighborMergedColor;}
00088         const QColor & getRejectedLoopClosureColor() const {return _loopClosureRejectedColor;}
00089         const QColor & getLocalPathColor() const {return _localPathColor;}
00090         const QColor & getGlobalPathColor() const {return _globalPathColor;}
00091         const QColor & getGTColor() const {return _gtPathColor;}
00092         const QColor & getIntraSessionLoopColor() const {return _loopIntraSessionColor;}
00093         const QColor & getInterSessionLoopColor() const {return _loopInterSessionColor;}
00094         bool isIntraInterSessionColorsEnabled() const {return _intraInterSessionColors;}
00095         bool isGridMapVisible() const;
00096         bool isOriginVisible() const;
00097         bool isReferentialVisible() const;
00098         bool isLocalRadiusVisible() const;
00099         float getLoopClosureOutlierThr() const {return _loopClosureOutlierThr;}
00100         float getMaxLinkLength() const {return _maxLinkLength;}
00101         bool isGraphVisible() const;
00102         bool isGlobalPathVisible() const;
00103         bool isLocalPathVisible() const;
00104         bool isGtGraphVisible() const;
00105 
00106         // setters
00107         void setWorkingDirectory(const QString & path);
00108         void setNodeRadius(float radius);
00109         void setLinkWidth(float width);
00110         void setNodeColor(const QColor & color);
00111         void setCurrentGoalColor(const QColor & color);
00112         void setNeighborColor(const QColor & color);
00113         void setGlobalLoopClosureColor(const QColor & color);
00114         void setLocalLoopClosureColor(const QColor & color);
00115         void setUserLoopClosureColor(const QColor & color);
00116         void setVirtualLoopClosureColor(const QColor & color);
00117         void setNeighborMergedColor(const QColor & color);
00118         void setRejectedLoopClosureColor(const QColor & color);
00119         void setLocalPathColor(const QColor & color);
00120         void setGlobalPathColor(const QColor & color);
00121         void setGTColor(const QColor & color);
00122         void setIntraSessionLoopColor(const QColor & color);
00123         void setInterSessionLoopColor(const QColor & color);
00124         void setIntraInterSessionColorsEnabled(bool enabled);
00125         void setGridMapVisible(bool visible);
00126         void setOriginVisible(bool visible);
00127         void setReferentialVisible(bool visible);
00128         void setLocalRadiusVisible(bool visible);
00129         void setLoopClosureOutlierThr(float value);
00130         void setMaxLinkLength(float value);
00131         void setGraphVisible(bool visible);
00132         void setGlobalPathVisible(bool visible);
00133         void setLocalPathVisible(bool visible);
00134         void setGtGraphVisible(bool visible);
00135 
00136 signals:
00137         void configChanged();
00138 
00139 public slots:
00140         void restoreDefaults();
00141 
00142 protected:
00143         virtual void wheelEvent ( QWheelEvent * event );
00144         virtual void contextMenuEvent(QContextMenuEvent * event);
00145 
00146 private:
00147         QString _workingDirectory;
00148         QColor _nodeColor;
00149         QColor _currentGoalColor;
00150         QColor _neighborColor;
00151         QColor _loopClosureColor;
00152         QColor _loopClosureLocalColor;
00153         QColor _loopClosureUserColor;
00154         QColor _loopClosureVirtualColor;
00155         QColor _neighborMergedColor;
00156         QColor _loopClosureRejectedColor;
00157         QColor _localPathColor;
00158         QColor _globalPathColor;
00159         QColor _gtPathColor;
00160         QColor _loopIntraSessionColor;
00161         QColor _loopInterSessionColor;
00162         bool _intraInterSessionColors;
00163         QGraphicsItem * _root;
00164         QGraphicsItem * _graphRoot;
00165         QGraphicsItem * _globalPathRoot;
00166         QGraphicsItem * _localPathRoot;
00167         QGraphicsItem * _gtGraphRoot;
00168         QMap<int, NodeItem*> _nodeItems;
00169         QMultiMap<int, LinkItem*> _linkItems;
00170         QMap<int, NodeItem*> _gtNodeItems;
00171         QMultiMap<int, LinkItem*> _gtLinkItems;
00172         QMultiMap<int, LinkItem*> _localPathLinkItems;
00173         QMultiMap<int, LinkItem*> _globalPathLinkItems;
00174         float _nodeRadius;
00175         float _linkWidth;
00176         QGraphicsPixmapItem * _gridMap;
00177         QGraphicsItemGroup * _referential;
00178         QGraphicsItemGroup * _originReferential;
00179         float _gridCellSize;
00180         QGraphicsEllipseItem * _localRadius;
00181         float _loopClosureOutlierThr;
00182         float _maxLinkLength;
00183 };
00184 
00185 } /* namespace rtabmap */
00186 #endif /* GRAPHVIEWER_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16