Public Member Functions | Protected Member Functions | Private Slots | Private Member Functions | Private Attributes
rtabmap::DatabaseViewer Class Reference

#include <DatabaseViewer.h>

List of all members.

Public Member Functions

 DatabaseViewer (const QString &ini=QString(), QWidget *parent=0)
bool isSavedMaximized () const
bool openDatabase (const QString &path)
void showCloseButton (bool visible=true)
virtual ~DatabaseViewer ()

Protected Member Functions

virtual void closeEvent (QCloseEvent *event)
virtual bool eventFilter (QObject *obj, QEvent *event)
virtual void keyPressEvent (QKeyEvent *event)
virtual void moveEvent (QMoveEvent *anEvent)
virtual void resizeEvent (QResizeEvent *anEvent)
virtual void showEvent (QShowEvent *anEvent)

Private Slots

void addConstraint ()
bool closeDatabase ()
void configModified ()
void detectMoreLoopClosures ()
void editDepthImage ()
void exportDatabase ()
void exportGPS_KML ()
void exportGPS_TXT ()
void exportOptimizedMesh ()
void exportPosesG2O ()
void exportPosesKITTI ()
void exportPosesKML ()
void exportPosesRaw ()
void exportPosesRGBDSLAM ()
void exportPosesTORO ()
void exportSaved2DMap ()
void extractImages ()
void generate3DMap ()
void generateGraph ()
void generateLocalGraph ()
void import2DMap ()
void notifyParametersChanged (const QStringList &)
void openDatabase ()
void recoverDatabase ()
void refineAllLoopClosureLinks ()
void refineAllNeighborLinks ()
void refineConstraint ()
void regenerateCurrentLocalMaps ()
void regenerateLocalMaps ()
void rejectConstraint ()
void resetAllChanges ()
void resetConstraint ()
void restoreDefaultSettings ()
void selectEmptyColor ()
void selectGroundColor ()
void selectObstacleColor ()
void setupMainLayout (bool vertical)
void sliderAMoved (int)
void sliderAValueChanged (int)
void sliderBMoved (int)
void sliderBValueChanged (int)
void sliderIterationsValueChanged (int)
void sliderLoopValueChanged (int)
void sliderNeighborValueChanged (int)
void update3dView ()
void updateConstraintView ()
void updateGraphView ()
void updateGrid ()
void updateLoggerLevel ()
void updateOctomapView ()
void updateOptimizedMesh ()
void updateStatistics ()
void updateStereo ()
void view3DMap ()
void viewOptimizedMesh ()
void writeSettings ()

Private Member Functions

bool addConstraint (int from, int to, bool silent)
bool containsLink (std::multimap< int, Link > &links, int from, int to)
void exportGPS (int format)
void exportPoses (int format)
Link findActiveLink (int from, int to)
QString getIniFilePath () const
void readSettings ()
void refineConstraint (int from, int to, bool silent)
void update (int value, QLabel *labelIndex, QLabel *labelParents, QLabel *labelChildren, QLabel *weight, QLabel *label, QLabel *stamp, rtabmap::ImageView *view, QLabel *labelId, QLabel *labelMapId, QLabel *labelPose, QLabel *labelVelocity, QLabel *labeCalib, QLabel *labelGps, bool updateConstraintView)
void updateConstraintButtons ()
void updateConstraintView (const rtabmap::Link &link, bool updateImageSliders=true, const Signature &signatureFrom=Signature(0), const Signature &signatureTo=Signature(0))
void updateIds ()
std::multimap< int, rtabmap::LinkupdateLinksWithModifications (const std::multimap< int, rtabmap::Link > &edgeConstraints)
void updateLoopClosuresSlider (int from=0, int to=0)
void updateStereo (const SensorData *data)
void updateWordsMatching ()

Private Attributes

CloudViewercloudViewer_
CloudViewerconstraintsViewer_
std::string databaseFileName_
rtabmap::DBDriverdbDriver_
EditDepthAreaeditDepthArea_
QDialog * editDepthDialog_
ExportCloudsDialogexportDialog_
bool firstCall_
std::map< int, std::pair
< std::pair< cv::Mat, cv::Mat >
, cv::Mat > > 
generatedLocalMaps_
std::map< int, std::pair
< float, cv::Point3f > > 
generatedLocalMapsInfo_
std::map< int, rtabmap::TransformgpsPoses_
std::map< int, GPSgpsValues_
std::list< std::map< int,
rtabmap::Transform > > 
graphes_
std::multimap< int, rtabmap::LinkgraphLinks_
std::map< int, rtabmap::TransformgroundTruthPoses_
QList< int > ids_
QMap< int, int > idToIndex_
QString iniFilePath_
std::map< int, TransformlastOptimizedGraph_
std::multimap< int, rtabmap::Linklinks_
std::multimap< int, rtabmap::LinklinksAdded_
std::multimap< int, rtabmap::LinklinksRefined_
std::multimap< int, rtabmap::LinklinksRemoved_
std::map< int, std::pair
< std::pair< cv::Mat, cv::Mat >
, cv::Mat > > 
localMaps_
std::map< int, std::pair
< float, cv::Point3f > > 
localMapsInfo_
QList< rtabmap::LinkloopLinks_
std::map< int, int > mapIds_
std::map< int, cv::Mat > modifiedDepthImages_
QList< rtabmap::LinkneighborLinks_
CloudVieweroccupancyGridViewer_
OctoMapoctomap_
std::map< int, rtabmap::TransformodomPoses_
QString pathDatabase_
bool savedMaximized_
CloudViewerstereoViewer_
Ui_DatabaseViewer * ui_
bool useLastOptimizedGraphAsGuess_
std::map< int, int > weights_
std::map< int, std::vector< int > > wmStates_

Detailed Description

Definition at line 64 of file DatabaseViewer.h.


Constructor & Destructor Documentation

rtabmap::DatabaseViewer::DatabaseViewer ( const QString &  ini = QString(),
QWidget *  parent = 0 
)

Definition at line 97 of file DatabaseViewer.cpp.

Definition at line 423 of file DatabaseViewer.cpp.


Member Function Documentation

void rtabmap::DatabaseViewer::addConstraint ( ) [private, slot]

Definition at line 6127 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::addConstraint ( int  from,
int  to,
bool  silent 
) [private]

Definition at line 6134 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::closeDatabase ( ) [private, slot]

Definition at line 816 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::closeEvent ( QCloseEvent *  event) [protected, virtual]

Definition at line 1058 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::configModified ( ) [private, slot]

Definition at line 453 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::containsLink ( std::multimap< int, Link > &  links,
int  from,
int  to 
) [private]

Definition at line 5788 of file DatabaseViewer.cpp.

Definition at line 3183 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::editDepthImage ( ) [private, slot]

Definition at line 1932 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::eventFilter ( QObject *  obj,
QEvent *  event 
) [protected, virtual]

Definition at line 1142 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportDatabase ( ) [private, slot]

Definition at line 1152 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportGPS ( int  format) [private]

Definition at line 2333 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportGPS_KML ( ) [private, slot]

Definition at line 2328 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportGPS_TXT ( ) [private, slot]

Definition at line 2324 of file DatabaseViewer.cpp.

Definition at line 2493 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPoses ( int  format) [private]

Definition at line 1981 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesG2O ( ) [private, slot]

Definition at line 1972 of file DatabaseViewer.cpp.

Definition at line 1964 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesKML ( ) [private, slot]

Definition at line 1976 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesRaw ( ) [private, slot]

Definition at line 1956 of file DatabaseViewer.cpp.

Definition at line 1960 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesTORO ( ) [private, slot]

Definition at line 1968 of file DatabaseViewer.cpp.

Definition at line 2366 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::extractImages ( ) [private, slot]

Definition at line 1317 of file DatabaseViewer.cpp.

Link rtabmap::DatabaseViewer::findActiveLink ( int  from,
int  to 
) [private]

Definition at line 5761 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::generate3DMap ( ) [private, slot]

Definition at line 3132 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::generateGraph ( ) [private, slot]

Definition at line 2735 of file DatabaseViewer.cpp.

Definition at line 2750 of file DatabaseViewer.cpp.

QString rtabmap::DatabaseViewer::getIniFilePath ( ) const [private]

Definition at line 458 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::import2DMap ( ) [private, slot]

Definition at line 2402 of file DatabaseViewer.cpp.

Definition at line 72 of file DatabaseViewer.h.

void rtabmap::DatabaseViewer::keyPressEvent ( QKeyEvent *  event) [protected, virtual]

Definition at line 1133 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::moveEvent ( QMoveEvent *  anEvent) [protected, virtual]

Definition at line 1112 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::notifyParametersChanged ( const QStringList &  parametersChanged) [private, slot]

Definition at line 6635 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::openDatabase ( const QString &  path)

Definition at line 705 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::openDatabase ( ) [private, slot]

Definition at line 696 of file DatabaseViewer.cpp.

Definition at line 472 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::recoverDatabase ( ) [private, slot]

Definition at line 1029 of file DatabaseViewer.cpp.

Definition at line 3315 of file DatabaseViewer.cpp.

Definition at line 3283 of file DatabaseViewer.cpp.

Definition at line 5793 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::refineConstraint ( int  from,
int  to,
bool  silent 
) [private]

Definition at line 5800 of file DatabaseViewer.cpp.

Definition at line 2971 of file DatabaseViewer.cpp.

Definition at line 2836 of file DatabaseViewer.cpp.

Definition at line 6453 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::resetAllChanges ( ) [private, slot]

Definition at line 3347 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::resetConstraint ( ) [private, slot]

Definition at line 6416 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::resizeEvent ( QResizeEvent *  anEvent) [protected, virtual]

Definition at line 1125 of file DatabaseViewer.cpp.

Definition at line 647 of file DatabaseViewer.cpp.

Definition at line 1924 of file DatabaseViewer.cpp.

Definition at line 1916 of file DatabaseViewer.cpp.

Definition at line 1908 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::setupMainLayout ( bool  vertical) [private, slot]

Definition at line 432 of file DatabaseViewer.cpp.

Definition at line 448 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::showEvent ( QShowEvent *  anEvent) [protected, virtual]

Definition at line 1102 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderAMoved ( int  value) [private, slot]

Definition at line 4332 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderAValueChanged ( int  value) [private, slot]

Definition at line 3358 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderBMoved ( int  value) [private, slot]

Definition at line 4345 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderBValueChanged ( int  value) [private, slot]

Definition at line 3377 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderIterationsValueChanged ( int  value) [private, slot]

Definition at line 4948 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderLoopValueChanged ( int  value) [private, slot]

Definition at line 4375 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::sliderNeighborValueChanged ( int  value) [private, slot]

Definition at line 4367 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::update ( int  value,
QLabel *  labelIndex,
QLabel *  labelParents,
QLabel *  labelChildren,
QLabel *  weight,
QLabel *  label,
QLabel *  stamp,
rtabmap::ImageView view,
QLabel *  labelId,
QLabel *  labelMapId,
QLabel *  labelPose,
QLabel *  labelVelocity,
QLabel *  labeCalib,
QLabel *  labelGps,
bool  updateConstraintView 
) [private]

Definition at line 3396 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::update3dView ( ) [private, slot]

Definition at line 4358 of file DatabaseViewer.cpp.

Definition at line 4901 of file DatabaseViewer.cpp.

Definition at line 4384 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateConstraintView ( const rtabmap::Link link,
bool  updateImageSliders = true,
const Signature signatureFrom = Signature(0),
const Signature signatureTo = Signature(0) 
) [private]

Definition at line 4404 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateGraphView ( ) [private, slot]

Definition at line 5343 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateGrid ( ) [private, slot]

Definition at line 5667 of file DatabaseViewer.cpp.

Definition at line 1453 of file DatabaseViewer.cpp.

std::multimap< int, rtabmap::Link > rtabmap::DatabaseViewer::updateLinksWithModifications ( const std::multimap< int, rtabmap::Link > &  edgeConstraints) [private]

Definition at line 6506 of file DatabaseViewer.cpp.

Definition at line 4074 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateLoopClosuresSlider ( int  from = 0,
int  to = 0 
) [private]

Definition at line 6568 of file DatabaseViewer.cpp.

Definition at line 5689 of file DatabaseViewer.cpp.

Definition at line 2608 of file DatabaseViewer.cpp.

Definition at line 1856 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateStereo ( ) [private, slot]

Definition at line 4082 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateStereo ( const SensorData data) [private]

Definition at line 4094 of file DatabaseViewer.cpp.

Definition at line 4269 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::view3DMap ( ) [private, slot]

Definition at line 3081 of file DatabaseViewer.cpp.

Definition at line 2441 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::writeSettings ( ) [private, slot]

Definition at line 557 of file DatabaseViewer.cpp.


Member Data Documentation

Definition at line 185 of file DatabaseViewer.h.

Definition at line 184 of file DatabaseViewer.h.

Definition at line 197 of file DatabaseViewer.h.

Definition at line 195 of file DatabaseViewer.h.

Definition at line 216 of file DatabaseViewer.h.

Definition at line 215 of file DatabaseViewer.h.

Definition at line 214 of file DatabaseViewer.h.

Definition at line 219 of file DatabaseViewer.h.

std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > rtabmap::DatabaseViewer::generatedLocalMaps_ [private]

Definition at line 210 of file DatabaseViewer.h.

std::map<int, std::pair<float, cv::Point3f> > rtabmap::DatabaseViewer::generatedLocalMapsInfo_ [private]

Definition at line 211 of file DatabaseViewer.h.

Definition at line 202 of file DatabaseViewer.h.

std::map<int, GPS> rtabmap::DatabaseViewer::gpsValues_ [private]

Definition at line 203 of file DatabaseViewer.h.

std::list<std::map<int, rtabmap::Transform> > rtabmap::DatabaseViewer::graphes_ [private]

Definition at line 198 of file DatabaseViewer.h.

std::multimap<int, rtabmap::Link> rtabmap::DatabaseViewer::graphLinks_ [private]

Definition at line 199 of file DatabaseViewer.h.

Definition at line 201 of file DatabaseViewer.h.

QList<int> rtabmap::DatabaseViewer::ids_ [private]

Definition at line 188 of file DatabaseViewer.h.

QMap<int, int> rtabmap::DatabaseViewer::idToIndex_ [private]

Definition at line 192 of file DatabaseViewer.h.

Definition at line 220 of file DatabaseViewer.h.

Definition at line 223 of file DatabaseViewer.h.

std::multimap<int, rtabmap::Link> rtabmap::DatabaseViewer::links_ [private]

Definition at line 204 of file DatabaseViewer.h.

std::multimap<int, rtabmap::Link> rtabmap::DatabaseViewer::linksAdded_ [private]

Definition at line 206 of file DatabaseViewer.h.

Definition at line 205 of file DatabaseViewer.h.

Definition at line 207 of file DatabaseViewer.h.

std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > rtabmap::DatabaseViewer::localMaps_ [private]

Definition at line 208 of file DatabaseViewer.h.

std::map<int, std::pair<float, cv::Point3f> > rtabmap::DatabaseViewer::localMapsInfo_ [private]

Definition at line 209 of file DatabaseViewer.h.

Definition at line 194 of file DatabaseViewer.h.

std::map<int, int> rtabmap::DatabaseViewer::mapIds_ [private]

Definition at line 189 of file DatabaseViewer.h.

std::map<int, cv::Mat> rtabmap::DatabaseViewer::modifiedDepthImages_ [private]

Definition at line 212 of file DatabaseViewer.h.

Definition at line 193 of file DatabaseViewer.h.

Definition at line 187 of file DatabaseViewer.h.

Definition at line 213 of file DatabaseViewer.h.

Definition at line 200 of file DatabaseViewer.h.

Definition at line 196 of file DatabaseViewer.h.

Definition at line 218 of file DatabaseViewer.h.

Definition at line 186 of file DatabaseViewer.h.

Ui_DatabaseViewer* rtabmap::DatabaseViewer::ui_ [private]

Definition at line 183 of file DatabaseViewer.h.

Definition at line 222 of file DatabaseViewer.h.

std::map<int, int> rtabmap::DatabaseViewer::weights_ [private]

Definition at line 190 of file DatabaseViewer.h.

std::map<int, std::vector<int> > rtabmap::DatabaseViewer::wmStates_ [private]

Definition at line 191 of file DatabaseViewer.h.


The documentation for this class was generated from the following files:


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