Public Member Functions | Protected Member Functions | Private Slots | Private Member Functions | Private Attributes | List of all members
rtabmap::DatabaseViewer Class Reference

#include <DatabaseViewer.h>

Inheritance diagram for rtabmap::DatabaseViewer:
Inheritance graph
[legend]

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 editConstraint ()
 
void editDepthImage ()
 
void editSaved2DMap ()
 
void exportDatabase ()
 
void exportGPS_KML ()
 
void exportGPS_TXT ()
 
void exportOptimizedMesh ()
 
void exportPosesG2O ()
 
void exportPosesKITTI ()
 
void exportPosesKML ()
 
void exportPosesRaw ()
 
void exportPosesRGBDSLAM ()
 
void exportPosesRGBDSLAMID ()
 
void exportPosesRGBDSLAMMotionCapture ()
 
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 regenerateSavedMap ()
 
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 updateAllLandmarkCovariances ()
 
void updateAllLoopClosureCovariances ()
 
void updateAllNeighborCovariances ()
 
void updateConstraintButtons ()
 
void updateConstraintView ()
 
void updateGraphView ()
 
void updateGrid ()
 
void updateInfo ()
 
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 refineAllLinks (const QList< Link > &links)
 
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 *labelOptPose, QLabel *labelVelocity, QLabel *labelCalib, QLabel *labelScan, QLabel *labelGravity, QLabel *labelPrior, QLabel *labelGps, QLabel *labelGt, QLabel *labelSensors, bool updateConstraintView)
 
void updateAllCovariances (const QList< Link > &links)
 
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 (const std::vector< int > &inliers=std::vector< int >())
 

Private Attributes

CloudViewercloudViewer_
 
CloudViewerconstraintsViewer_
 
std::string databaseFileName_
 
rtabmap::DBDriverdbDriver_
 
EditDepthAreaeditDepthArea_
 
QDialog * editDepthDialog_
 
EditMapAreaeditMapArea_
 
QDialog * editMapDialog_
 
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_
 
bool infoReducedGraph_
 
int infoSessions_
 
double infoTotalOdom_
 
double infoTotalTime_
 
QString iniFilePath_
 
int lastSliderIndexBrowsed_
 
std::set< int > lastWmIds_
 
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, LaserScanmodifiedLaserScans_
 
QList< rtabmap::LinkneighborLinks_
 
CloudVieweroccupancyGridViewer_
 
OctoMapoctomap_
 
std::vector< double > odomMaxInf_
 
std::map< int, rtabmap::TransformodomPoses_
 
QString pathDatabase_
 
bool savedMaximized_
 
CloudViewerstereoViewer_
 
Ui_DatabaseViewer * ui_
 
std::map< int, int > weights_
 
std::map< int, std::vector< int > > wmStates_
 

Detailed Description

Definition at line 65 of file DatabaseViewer.h.

Constructor & Destructor Documentation

◆ DatabaseViewer()

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

Definition at line 103 of file DatabaseViewer.cpp.

◆ ~DatabaseViewer()

rtabmap::DatabaseViewer::~DatabaseViewer ( )
virtual

Definition at line 477 of file DatabaseViewer.cpp.

Member Function Documentation

◆ addConstraint [1/2]

void rtabmap::DatabaseViewer::addConstraint ( )
privateslot

Definition at line 8164 of file DatabaseViewer.cpp.

◆ addConstraint() [2/2]

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

Definition at line 8171 of file DatabaseViewer.cpp.

◆ closeDatabase

bool rtabmap::DatabaseViewer::closeDatabase ( )
privateslot

Definition at line 892 of file DatabaseViewer.cpp.

◆ closeEvent()

void rtabmap::DatabaseViewer::closeEvent ( QCloseEvent *  event)
protectedvirtual

Definition at line 1176 of file DatabaseViewer.cpp.

◆ configModified

void rtabmap::DatabaseViewer::configModified ( )
privateslot

Definition at line 507 of file DatabaseViewer.cpp.

◆ containsLink()

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

Definition at line 7634 of file DatabaseViewer.cpp.

◆ detectMoreLoopClosures

void rtabmap::DatabaseViewer::detectMoreLoopClosures ( )
privateslot

Definition at line 4087 of file DatabaseViewer.cpp.

◆ editConstraint

void rtabmap::DatabaseViewer::editConstraint ( )
privateslot

Definition at line 5787 of file DatabaseViewer.cpp.

◆ editDepthImage

void rtabmap::DatabaseViewer::editDepthImage ( )
privateslot

Definition at line 2315 of file DatabaseViewer.cpp.

◆ editSaved2DMap

void rtabmap::DatabaseViewer::editSaved2DMap ( )
privateslot

Definition at line 2829 of file DatabaseViewer.cpp.

◆ eventFilter()

bool rtabmap::DatabaseViewer::eventFilter ( QObject *  obj,
QEvent *  event 
)
protectedvirtual

Definition at line 1260 of file DatabaseViewer.cpp.

◆ exportDatabase

void rtabmap::DatabaseViewer::exportDatabase ( )
privateslot

Definition at line 1270 of file DatabaseViewer.cpp.

◆ exportGPS()

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

Definition at line 2796 of file DatabaseViewer.cpp.

◆ exportGPS_KML

void rtabmap::DatabaseViewer::exportGPS_KML ( )
privateslot

Definition at line 2791 of file DatabaseViewer.cpp.

◆ exportGPS_TXT

void rtabmap::DatabaseViewer::exportGPS_TXT ( )
privateslot

Definition at line 2787 of file DatabaseViewer.cpp.

◆ exportOptimizedMesh

void rtabmap::DatabaseViewer::exportOptimizedMesh ( )
privateslot

Definition at line 3357 of file DatabaseViewer.cpp.

◆ exportPoses()

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

Definition at line 2377 of file DatabaseViewer.cpp.

◆ exportPosesG2O

void rtabmap::DatabaseViewer::exportPosesG2O ( )
privateslot

Definition at line 2368 of file DatabaseViewer.cpp.

◆ exportPosesKITTI

void rtabmap::DatabaseViewer::exportPosesKITTI ( )
privateslot

Definition at line 2360 of file DatabaseViewer.cpp.

◆ exportPosesKML

void rtabmap::DatabaseViewer::exportPosesKML ( )
privateslot

Definition at line 2372 of file DatabaseViewer.cpp.

◆ exportPosesRaw

void rtabmap::DatabaseViewer::exportPosesRaw ( )
privateslot

Definition at line 2344 of file DatabaseViewer.cpp.

◆ exportPosesRGBDSLAM

void rtabmap::DatabaseViewer::exportPosesRGBDSLAM ( )
privateslot

Definition at line 2352 of file DatabaseViewer.cpp.

◆ exportPosesRGBDSLAMID

void rtabmap::DatabaseViewer::exportPosesRGBDSLAMID ( )
privateslot

Definition at line 2356 of file DatabaseViewer.cpp.

◆ exportPosesRGBDSLAMMotionCapture

void rtabmap::DatabaseViewer::exportPosesRGBDSLAMMotionCapture ( )
privateslot

Definition at line 2348 of file DatabaseViewer.cpp.

◆ exportPosesTORO

void rtabmap::DatabaseViewer::exportPosesTORO ( )
privateslot

Definition at line 2364 of file DatabaseViewer.cpp.

◆ exportSaved2DMap

void rtabmap::DatabaseViewer::exportSaved2DMap ( )
privateslot

Definition at line 3105 of file DatabaseViewer.cpp.

◆ extractImages

void rtabmap::DatabaseViewer::extractImages ( )
privateslot

Definition at line 1445 of file DatabaseViewer.cpp.

◆ findActiveLink()

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

Definition at line 7607 of file DatabaseViewer.cpp.

◆ generate3DMap

void rtabmap::DatabaseViewer::generate3DMap ( )
privateslot

Definition at line 4036 of file DatabaseViewer.cpp.

◆ generateGraph

void rtabmap::DatabaseViewer::generateGraph ( )
privateslot

Definition at line 3603 of file DatabaseViewer.cpp.

◆ generateLocalGraph

void rtabmap::DatabaseViewer::generateLocalGraph ( )
privateslot

Definition at line 3618 of file DatabaseViewer.cpp.

◆ getIniFilePath()

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

Definition at line 512 of file DatabaseViewer.cpp.

◆ import2DMap

void rtabmap::DatabaseViewer::import2DMap ( )
privateslot

Definition at line 3141 of file DatabaseViewer.cpp.

◆ isSavedMaximized()

bool rtabmap::DatabaseViewer::isSavedMaximized ( ) const
inline

Definition at line 73 of file DatabaseViewer.h.

◆ keyPressEvent()

void rtabmap::DatabaseViewer::keyPressEvent ( QKeyEvent *  event)
protectedvirtual

Definition at line 1251 of file DatabaseViewer.cpp.

◆ moveEvent()

void rtabmap::DatabaseViewer::moveEvent ( QMoveEvent *  anEvent)
protectedvirtual

Definition at line 1230 of file DatabaseViewer.cpp.

◆ notifyParametersChanged

void rtabmap::DatabaseViewer::notifyParametersChanged ( const QStringList &  parametersChanged)
privateslot

Definition at line 8828 of file DatabaseViewer.cpp.

◆ openDatabase() [1/2]

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

Definition at line 780 of file DatabaseViewer.cpp.

◆ openDatabase [2/2]

void rtabmap::DatabaseViewer::openDatabase ( )
privateslot

Definition at line 771 of file DatabaseViewer.cpp.

◆ readSettings()

void rtabmap::DatabaseViewer::readSettings ( )
private

Definition at line 526 of file DatabaseViewer.cpp.

◆ recoverDatabase

void rtabmap::DatabaseViewer::recoverDatabase ( )
privateslot

Definition at line 1147 of file DatabaseViewer.cpp.

◆ refineAllLinks()

void rtabmap::DatabaseViewer::refineAllLinks ( const QList< Link > &  links)
private

Definition at line 4352 of file DatabaseViewer.cpp.

◆ refineAllLoopClosureLinks

void rtabmap::DatabaseViewer::refineAllLoopClosureLinks ( )
privateslot

Definition at line 4348 of file DatabaseViewer.cpp.

◆ refineAllNeighborLinks

void rtabmap::DatabaseViewer::refineAllNeighborLinks ( )
privateslot

Definition at line 4344 of file DatabaseViewer.cpp.

◆ refineConstraint [1/2]

void rtabmap::DatabaseViewer::refineConstraint ( )
privateslot

Definition at line 7639 of file DatabaseViewer.cpp.

◆ refineConstraint() [2/2]

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

Definition at line 7646 of file DatabaseViewer.cpp.

◆ regenerateCurrentLocalMaps

void rtabmap::DatabaseViewer::regenerateCurrentLocalMaps ( )
privateslot

Definition at line 3857 of file DatabaseViewer.cpp.

◆ regenerateLocalMaps

void rtabmap::DatabaseViewer::regenerateLocalMaps ( )
privateslot

Definition at line 3704 of file DatabaseViewer.cpp.

◆ regenerateSavedMap

void rtabmap::DatabaseViewer::regenerateSavedMap ( )
privateslot

Definition at line 3196 of file DatabaseViewer.cpp.

◆ rejectConstraint

void rtabmap::DatabaseViewer::rejectConstraint ( )
privateslot

Definition at line 8645 of file DatabaseViewer.cpp.

◆ resetAllChanges

void rtabmap::DatabaseViewer::resetAllChanges ( )
privateslot

Definition at line 4390 of file DatabaseViewer.cpp.

◆ resetConstraint

void rtabmap::DatabaseViewer::resetConstraint ( )
privateslot

Definition at line 8609 of file DatabaseViewer.cpp.

◆ resizeEvent()

void rtabmap::DatabaseViewer::resizeEvent ( QResizeEvent *  anEvent)
protectedvirtual

Definition at line 1243 of file DatabaseViewer.cpp.

◆ restoreDefaultSettings

void rtabmap::DatabaseViewer::restoreDefaultSettings ( )
privateslot

Definition at line 715 of file DatabaseViewer.cpp.

◆ selectEmptyColor

void rtabmap::DatabaseViewer::selectEmptyColor ( )
privateslot

Definition at line 2307 of file DatabaseViewer.cpp.

◆ selectGroundColor

void rtabmap::DatabaseViewer::selectGroundColor ( )
privateslot

Definition at line 2299 of file DatabaseViewer.cpp.

◆ selectObstacleColor

void rtabmap::DatabaseViewer::selectObstacleColor ( )
privateslot

Definition at line 2291 of file DatabaseViewer.cpp.

◆ setupMainLayout

void rtabmap::DatabaseViewer::setupMainLayout ( bool  vertical)
privateslot

Definition at line 486 of file DatabaseViewer.cpp.

◆ showCloseButton()

void rtabmap::DatabaseViewer::showCloseButton ( bool  visible = true)

Definition at line 502 of file DatabaseViewer.cpp.

◆ showEvent()

void rtabmap::DatabaseViewer::showEvent ( QShowEvent *  anEvent)
protectedvirtual

Definition at line 1220 of file DatabaseViewer.cpp.

◆ sliderAMoved

void rtabmap::DatabaseViewer::sliderAMoved ( int  value)
privateslot

Definition at line 5733 of file DatabaseViewer.cpp.

◆ sliderAValueChanged

void rtabmap::DatabaseViewer::sliderAValueChanged ( int  value)
privateslot

Definition at line 4409 of file DatabaseViewer.cpp.

◆ sliderBMoved

void rtabmap::DatabaseViewer::sliderBMoved ( int  value)
privateslot

Definition at line 5746 of file DatabaseViewer.cpp.

◆ sliderBValueChanged

void rtabmap::DatabaseViewer::sliderBValueChanged ( int  value)
privateslot

Definition at line 4434 of file DatabaseViewer.cpp.

◆ sliderIterationsValueChanged

void rtabmap::DatabaseViewer::sliderIterationsValueChanged ( int  value)
privateslot

Definition at line 6626 of file DatabaseViewer.cpp.

◆ sliderLoopValueChanged

void rtabmap::DatabaseViewer::sliderLoopValueChanged ( int  value)
privateslot

Definition at line 5779 of file DatabaseViewer.cpp.

◆ sliderNeighborValueChanged

void rtabmap::DatabaseViewer::sliderNeighborValueChanged ( int  value)
privateslot

Definition at line 5771 of file DatabaseViewer.cpp.

◆ update()

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 *  labelOptPose,
QLabel *  labelVelocity,
QLabel *  labelCalib,
QLabel *  labelScan,
QLabel *  labelGravity,
QLabel *  labelPrior,
QLabel *  labelGps,
QLabel *  labelGt,
QLabel *  labelSensors,
bool  updateConstraintView 
)
private

Definition at line 4459 of file DatabaseViewer.cpp.

◆ update3dView

void rtabmap::DatabaseViewer::update3dView ( )
privateslot

Definition at line 5759 of file DatabaseViewer.cpp.

◆ updateAllCovariances()

void rtabmap::DatabaseViewer::updateAllCovariances ( const QList< Link > &  links)
private

Definition at line 4256 of file DatabaseViewer.cpp.

◆ updateAllLandmarkCovariances

void rtabmap::DatabaseViewer::updateAllLandmarkCovariances ( )
privateslot

Definition at line 4243 of file DatabaseViewer.cpp.

◆ updateAllLoopClosureCovariances

void rtabmap::DatabaseViewer::updateAllLoopClosureCovariances ( )
privateslot

Definition at line 4231 of file DatabaseViewer.cpp.

◆ updateAllNeighborCovariances

void rtabmap::DatabaseViewer::updateAllNeighborCovariances ( )
privateslot

Definition at line 4227 of file DatabaseViewer.cpp.

◆ updateConstraintButtons

void rtabmap::DatabaseViewer::updateConstraintButtons ( )
privateslot

Definition at line 6556 of file DatabaseViewer.cpp.

◆ updateConstraintView [1/2]

void rtabmap::DatabaseViewer::updateConstraintView ( )
privateslot

Definition at line 5895 of file DatabaseViewer.cpp.

◆ updateConstraintView() [2/2]

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 5922 of file DatabaseViewer.cpp.

◆ updateGraphView

void rtabmap::DatabaseViewer::updateGraphView ( )
privateslot

Definition at line 7120 of file DatabaseViewer.cpp.

◆ updateGrid

void rtabmap::DatabaseViewer::updateGrid ( )
privateslot

Definition at line 7481 of file DatabaseViewer.cpp.

◆ updateIds()

void rtabmap::DatabaseViewer::updateIds ( )
private

Definition at line 1652 of file DatabaseViewer.cpp.

◆ updateInfo

void rtabmap::DatabaseViewer::updateInfo ( )
privateslot

Definition at line 2118 of file DatabaseViewer.cpp.

◆ updateLinksWithModifications()

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

Definition at line 8711 of file DatabaseViewer.cpp.

◆ updateLoggerLevel

void rtabmap::DatabaseViewer::updateLoggerLevel ( )
privateslot

Definition at line 5455 of file DatabaseViewer.cpp.

◆ updateLoopClosuresSlider()

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

Definition at line 8761 of file DatabaseViewer.cpp.

◆ updateOctomapView

void rtabmap::DatabaseViewer::updateOctomapView ( )
privateslot

Definition at line 7503 of file DatabaseViewer.cpp.

◆ updateOptimizedMesh

void rtabmap::DatabaseViewer::updateOptimizedMesh ( )
privateslot

Definition at line 3472 of file DatabaseViewer.cpp.

◆ updateStatistics

void rtabmap::DatabaseViewer::updateStatistics ( )
privateslot

Definition at line 2244 of file DatabaseViewer.cpp.

◆ updateStereo [1/2]

void rtabmap::DatabaseViewer::updateStereo ( )
privateslot

Definition at line 5463 of file DatabaseViewer.cpp.

◆ updateStereo() [2/2]

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

Definition at line 5475 of file DatabaseViewer.cpp.

◆ updateWordsMatching()

void rtabmap::DatabaseViewer::updateWordsMatching ( const std::vector< int > &  inliers = std::vector<int>())
private

Definition at line 5651 of file DatabaseViewer.cpp.

◆ view3DMap

void rtabmap::DatabaseViewer::view3DMap ( )
privateslot

Definition at line 3985 of file DatabaseViewer.cpp.

◆ viewOptimizedMesh

void rtabmap::DatabaseViewer::viewOptimizedMesh ( )
privateslot

Definition at line 3305 of file DatabaseViewer.cpp.

◆ writeSettings

void rtabmap::DatabaseViewer::writeSettings ( )
privateslot

Definition at line 618 of file DatabaseViewer.cpp.

Member Data Documentation

◆ cloudViewer_

CloudViewer* rtabmap::DatabaseViewer::cloudViewer_
private

Definition at line 203 of file DatabaseViewer.h.

◆ constraintsViewer_

CloudViewer* rtabmap::DatabaseViewer::constraintsViewer_
private

Definition at line 202 of file DatabaseViewer.h.

◆ databaseFileName_

std::string rtabmap::DatabaseViewer::databaseFileName_
private

Definition at line 217 of file DatabaseViewer.h.

◆ dbDriver_

rtabmap::DBDriver* rtabmap::DatabaseViewer::dbDriver_
private

Definition at line 215 of file DatabaseViewer.h.

◆ editDepthArea_

EditDepthArea* rtabmap::DatabaseViewer::editDepthArea_
private

Definition at line 237 of file DatabaseViewer.h.

◆ editDepthDialog_

QDialog* rtabmap::DatabaseViewer::editDepthDialog_
private

Definition at line 236 of file DatabaseViewer.h.

◆ editMapArea_

EditMapArea* rtabmap::DatabaseViewer::editMapArea_
private

Definition at line 239 of file DatabaseViewer.h.

◆ editMapDialog_

QDialog* rtabmap::DatabaseViewer::editMapDialog_
private

Definition at line 238 of file DatabaseViewer.h.

◆ exportDialog_

ExportCloudsDialog* rtabmap::DatabaseViewer::exportDialog_
private

Definition at line 235 of file DatabaseViewer.h.

◆ firstCall_

bool rtabmap::DatabaseViewer::firstCall_
private

Definition at line 242 of file DatabaseViewer.h.

◆ generatedLocalMaps_

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

Definition at line 230 of file DatabaseViewer.h.

◆ generatedLocalMapsInfo_

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

Definition at line 231 of file DatabaseViewer.h.

◆ gpsPoses_

std::map<int, rtabmap::Transform> rtabmap::DatabaseViewer::gpsPoses_
private

Definition at line 222 of file DatabaseViewer.h.

◆ gpsValues_

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

Definition at line 223 of file DatabaseViewer.h.

◆ graphes_

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

Definition at line 218 of file DatabaseViewer.h.

◆ graphLinks_

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

Definition at line 219 of file DatabaseViewer.h.

◆ groundTruthPoses_

std::map<int, rtabmap::Transform> rtabmap::DatabaseViewer::groundTruthPoses_
private

Definition at line 221 of file DatabaseViewer.h.

◆ ids_

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

Definition at line 206 of file DatabaseViewer.h.

◆ idToIndex_

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

Definition at line 211 of file DatabaseViewer.h.

◆ infoReducedGraph_

bool rtabmap::DatabaseViewer::infoReducedGraph_
private

Definition at line 245 of file DatabaseViewer.h.

◆ infoSessions_

int rtabmap::DatabaseViewer::infoSessions_
private

Definition at line 248 of file DatabaseViewer.h.

◆ infoTotalOdom_

double rtabmap::DatabaseViewer::infoTotalOdom_
private

Definition at line 246 of file DatabaseViewer.h.

◆ infoTotalTime_

double rtabmap::DatabaseViewer::infoTotalTime_
private

Definition at line 247 of file DatabaseViewer.h.

◆ iniFilePath_

QString rtabmap::DatabaseViewer::iniFilePath_
private

Definition at line 243 of file DatabaseViewer.h.

◆ lastSliderIndexBrowsed_

int rtabmap::DatabaseViewer::lastSliderIndexBrowsed_
private

Definition at line 214 of file DatabaseViewer.h.

◆ lastWmIds_

std::set<int> rtabmap::DatabaseViewer::lastWmIds_
private

Definition at line 207 of file DatabaseViewer.h.

◆ links_

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

Definition at line 224 of file DatabaseViewer.h.

◆ linksAdded_

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

Definition at line 226 of file DatabaseViewer.h.

◆ linksRefined_

std::multimap<int, rtabmap::Link> rtabmap::DatabaseViewer::linksRefined_
private

Definition at line 225 of file DatabaseViewer.h.

◆ linksRemoved_

std::multimap<int, rtabmap::Link> rtabmap::DatabaseViewer::linksRemoved_
private

Definition at line 227 of file DatabaseViewer.h.

◆ localMaps_

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

Definition at line 228 of file DatabaseViewer.h.

◆ localMapsInfo_

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

Definition at line 229 of file DatabaseViewer.h.

◆ loopLinks_

QList<rtabmap::Link> rtabmap::DatabaseViewer::loopLinks_
private

Definition at line 213 of file DatabaseViewer.h.

◆ mapIds_

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

Definition at line 208 of file DatabaseViewer.h.

◆ modifiedLaserScans_

std::map<int, LaserScan> rtabmap::DatabaseViewer::modifiedLaserScans_
private

Definition at line 232 of file DatabaseViewer.h.

◆ neighborLinks_

QList<rtabmap::Link> rtabmap::DatabaseViewer::neighborLinks_
private

Definition at line 212 of file DatabaseViewer.h.

◆ occupancyGridViewer_

CloudViewer* rtabmap::DatabaseViewer::occupancyGridViewer_
private

Definition at line 205 of file DatabaseViewer.h.

◆ octomap_

OctoMap* rtabmap::DatabaseViewer::octomap_
private

Definition at line 234 of file DatabaseViewer.h.

◆ odomMaxInf_

std::vector<double> rtabmap::DatabaseViewer::odomMaxInf_
private

Definition at line 233 of file DatabaseViewer.h.

◆ odomPoses_

std::map<int, rtabmap::Transform> rtabmap::DatabaseViewer::odomPoses_
private

Definition at line 220 of file DatabaseViewer.h.

◆ pathDatabase_

QString rtabmap::DatabaseViewer::pathDatabase_
private

Definition at line 216 of file DatabaseViewer.h.

◆ savedMaximized_

bool rtabmap::DatabaseViewer::savedMaximized_
private

Definition at line 241 of file DatabaseViewer.h.

◆ stereoViewer_

CloudViewer* rtabmap::DatabaseViewer::stereoViewer_
private

Definition at line 204 of file DatabaseViewer.h.

◆ ui_

Ui_DatabaseViewer* rtabmap::DatabaseViewer::ui_
private

Definition at line 201 of file DatabaseViewer.h.

◆ weights_

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

Definition at line 209 of file DatabaseViewer.h.

◆ wmStates_

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

Definition at line 210 of file DatabaseViewer.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:39:00