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 RTABMAP_GRAPHVIEWER_H_
00029 #define RTABMAP_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 <rtabmap/core/GeodeticCoords.h>
00038 #include <opencv2/opencv.hpp>
00039 #include <map>
00040 #include <vector>
00041 
00042 class QGraphicsItem;
00043 class QGraphicsPixmapItem;
00044 class QGraphicsItemGroup;
00045 
00046 namespace rtabmap {
00047 
00048 class NodeItem;
00049 class LinkItem;
00050 
00051 class RTABMAPGUI_EXP GraphViewer : public QGraphicsView {
00052 
00053         Q_OBJECT;
00054 
00055 public:
00056         GraphViewer(QWidget * parent = 0);
00057         virtual ~GraphViewer();
00058 
00059         void updateGraph(const std::map<int, Transform> & poses,
00060                                          const std::multimap<int, Link> & constraints,
00061                                          const std::map<int, int> & mapIds);
00062         void updateGTGraph(const std::map<int, Transform> & poses);
00063         void updateGPSGraph(
00064                         const std::map<int, Transform> & gpsMapPoses,
00065                         const std::map<int, GPS> & gpsValues);
00066         void updateReferentialPosition(const Transform & t);
00067         void updateMap(const cv::Mat & map8U, float resolution, float xMin, float yMin);
00068         void updatePosterior(const std::map<int, float> & posterior, float fixedMax = 0.0f);
00069         void updateLocalPath(const std::vector<int> & localPath);
00070         void setGlobalPath(const std::vector<std::pair<int, Transform> > & globalPath);
00071         void setCurrentGoalID(int id, const Transform & pose = Transform());
00072         void setLocalRadius(float radius);
00073         void clearGraph();
00074         void clearMap();
00075         void clearPosterior();
00076         void clearAll();
00077 
00078         void saveSettings(QSettings & settings, const QString & group = "") const;
00079         void loadSettings(QSettings & settings, const QString & group = "");
00080 
00081         //getters
00082         const QString & getWorkingDirectory() const {return _workingDirectory;}
00083         float getNodeRadius() const {return _nodeRadius;}
00084         float getLinkWidth() const {return _linkWidth;}
00085         const QColor & getNodeColor() const {return _nodeColor;}
00086         const QColor & getCurrentGoalColor() const {return _currentGoalColor;}
00087         const QColor & getNeighborColor() const {return _neighborColor;}
00088         const QColor & getGlobalLoopClosureColor() const {return _loopClosureColor;}
00089         const QColor & getLocalLoopClosureColor() const {return _loopClosureLocalColor;}
00090         const QColor & getUserLoopClosureColor() const {return _loopClosureUserColor;}
00091         const QColor & getVirtualLoopClosureColor() const {return _loopClosureVirtualColor;}
00092         const QColor & getNeighborMergedColor() const {return _neighborMergedColor;}
00093         const QColor & getRejectedLoopClosureColor() const {return _loopClosureRejectedColor;}
00094         const QColor & getLocalPathColor() const {return _localPathColor;}
00095         const QColor & getGlobalPathColor() const {return _globalPathColor;}
00096         const QColor & getGTColor() const {return _gtPathColor;}
00097         const QColor & getGPSColor() const {return _gpsPathColor;}
00098         const QColor & getIntraSessionLoopColor() const {return _loopIntraSessionColor;}
00099         const QColor & getInterSessionLoopColor() const {return _loopInterSessionColor;}
00100         bool isIntraInterSessionColorsEnabled() const {return _intraInterSessionColors;}
00101         bool isGridMapVisible() const;
00102         bool isOriginVisible() const;
00103         bool isReferentialVisible() const;
00104         bool isLocalRadiusVisible() const;
00105         float getLoopClosureOutlierThr() const {return _loopClosureOutlierThr;}
00106         float getMaxLinkLength() const {return _maxLinkLength;}
00107         bool isGraphVisible() const;
00108         bool isGlobalPathVisible() const;
00109         bool isLocalPathVisible() const;
00110         bool isGtGraphVisible() const;
00111         bool isGPSGraphVisible() const;
00112         bool isOrientationENU() const;
00113 
00114         // setters
00115         void setWorkingDirectory(const QString & path);
00116         void setNodeVisible(bool visible);
00117         void setNodeRadius(float radius);
00118         void setLinkWidth(float width);
00119         void setNodeColor(const QColor & color);
00120         void setCurrentGoalColor(const QColor & color);
00121         void setNeighborColor(const QColor & color);
00122         void setGlobalLoopClosureColor(const QColor & color);
00123         void setLocalLoopClosureColor(const QColor & color);
00124         void setUserLoopClosureColor(const QColor & color);
00125         void setVirtualLoopClosureColor(const QColor & color);
00126         void setNeighborMergedColor(const QColor & color);
00127         void setRejectedLoopClosureColor(const QColor & color);
00128         void setLocalPathColor(const QColor & color);
00129         void setGlobalPathColor(const QColor & color);
00130         void setGTColor(const QColor & color);
00131         void setGPSColor(const QColor & color);
00132         void setIntraSessionLoopColor(const QColor & color);
00133         void setInterSessionLoopColor(const QColor & color);
00134         void setIntraInterSessionColorsEnabled(bool enabled);
00135         void setGridMapVisible(bool visible);
00136         void setOriginVisible(bool visible);
00137         void setReferentialVisible(bool visible);
00138         void setLocalRadiusVisible(bool visible);
00139         void setLoopClosureOutlierThr(float value);
00140         void setMaxLinkLength(float value);
00141         void setGraphVisible(bool visible);
00142         void setGlobalPathVisible(bool visible);
00143         void setLocalPathVisible(bool visible);
00144         void setGtGraphVisible(bool visible);
00145         void setGPSGraphVisible(bool visible);
00146         void setOrientationENU(bool enabled);
00147 
00148 Q_SIGNALS:
00149         void configChanged();
00150         void mapShownRequested();
00151 
00152 public Q_SLOTS:
00153         void restoreDefaults();
00154 
00155 protected:
00156         virtual void wheelEvent ( QWheelEvent * event );
00157         virtual void contextMenuEvent(QContextMenuEvent * event);
00158 
00159 private:
00160         QString _workingDirectory;
00161         QColor _nodeColor;
00162         QColor _currentGoalColor;
00163         QColor _neighborColor;
00164         QColor _loopClosureColor;
00165         QColor _loopClosureLocalColor;
00166         QColor _loopClosureUserColor;
00167         QColor _loopClosureVirtualColor;
00168         QColor _neighborMergedColor;
00169         QColor _loopClosureRejectedColor;
00170         QColor _localPathColor;
00171         QColor _globalPathColor;
00172         QColor _gtPathColor;
00173         QColor _gpsPathColor;
00174         QColor _loopIntraSessionColor;
00175         QColor _loopInterSessionColor;
00176         bool _intraInterSessionColors;
00177         QGraphicsItem * _root;
00178         QGraphicsItem * _graphRoot;
00179         QGraphicsItem * _globalPathRoot;
00180         QGraphicsItem * _localPathRoot;
00181         QGraphicsItem * _gtGraphRoot;
00182         QGraphicsItem * _gpsGraphRoot;
00183         QMap<int, NodeItem*> _nodeItems;
00184         QMultiMap<int, LinkItem*> _linkItems;
00185         QMap<int, NodeItem*> _gtNodeItems;
00186         QMap<int, NodeItem*> _gpsNodeItems;
00187         QMultiMap<int, LinkItem*> _gtLinkItems;
00188         QMultiMap<int, LinkItem*> _gpsLinkItems;
00189         QMultiMap<int, LinkItem*> _localPathLinkItems;
00190         QMultiMap<int, LinkItem*> _globalPathLinkItems;
00191         bool _nodeVisible;
00192         float _nodeRadius;
00193         float _linkWidth;
00194         QGraphicsPixmapItem * _gridMap;
00195         QGraphicsItemGroup * _referential;
00196         QGraphicsItemGroup * _originReferential;
00197         float _gridCellSize;
00198         QGraphicsEllipseItem * _localRadius;
00199         float _loopClosureOutlierThr;
00200         float _maxLinkLength;
00201         bool _orientationENU;
00202 };
00203 
00204 } /* namespace rtabmap */
00205 #endif /* GRAPHVIEWER_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20