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 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 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 *labelVelocity, QLabel *labelCalib, QLabel *labelScan, QLabel *labelGravity, QLabel *labelGps, 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

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

Definition at line 102 of file DatabaseViewer.cpp.

rtabmap::DatabaseViewer::~DatabaseViewer ( )
virtual

Definition at line 466 of file DatabaseViewer.cpp.

Member Function Documentation

void rtabmap::DatabaseViewer::addConstraint ( )
privateslot

Definition at line 7461 of file DatabaseViewer.cpp.

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

Definition at line 7468 of file DatabaseViewer.cpp.

bool rtabmap::DatabaseViewer::closeDatabase ( )
privateslot

Definition at line 869 of file DatabaseViewer.cpp.

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

Definition at line 1153 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::configModified ( )
privateslot

Definition at line 496 of file DatabaseViewer.cpp.

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

Definition at line 6945 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::detectMoreLoopClosures ( )
privateslot

Definition at line 3818 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::editConstraint ( )
privateslot

Definition at line 5305 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::editDepthImage ( )
privateslot

Definition at line 2189 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::editSaved2DMap ( )
privateslot

Definition at line 2634 of file DatabaseViewer.cpp.

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

Definition at line 1237 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportDatabase ( )
privateslot

Definition at line 1247 of file DatabaseViewer.cpp.

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

Definition at line 2601 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportGPS_KML ( )
privateslot

Definition at line 2596 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportGPS_TXT ( )
privateslot

Definition at line 2592 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportOptimizedMesh ( )
privateslot

Definition at line 3122 of file DatabaseViewer.cpp.

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

Definition at line 2247 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesG2O ( )
privateslot

Definition at line 2238 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesKITTI ( )
privateslot

Definition at line 2230 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesKML ( )
privateslot

Definition at line 2242 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesRaw ( )
privateslot

Definition at line 2218 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesRGBDSLAM ( )
privateslot

Definition at line 2226 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesRGBDSLAMMotionCapture ( )
privateslot

Definition at line 2222 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportPosesTORO ( )
privateslot

Definition at line 2234 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::exportSaved2DMap ( )
privateslot

Definition at line 2910 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::extractImages ( )
privateslot

Definition at line 1422 of file DatabaseViewer.cpp.

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

Definition at line 6918 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::generate3DMap ( )
privateslot

Definition at line 3767 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::generateGraph ( )
privateslot

Definition at line 3368 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::generateLocalGraph ( )
privateslot

Definition at line 3383 of file DatabaseViewer.cpp.

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

Definition at line 501 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::import2DMap ( )
privateslot

Definition at line 2946 of file DatabaseViewer.cpp.

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

Definition at line 73 of file DatabaseViewer.h.

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

Definition at line 1228 of file DatabaseViewer.cpp.

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

Definition at line 1207 of file DatabaseViewer.cpp.

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

Definition at line 8053 of file DatabaseViewer.cpp.

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

Definition at line 757 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::openDatabase ( )
privateslot

Definition at line 748 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::readSettings ( )
private

Definition at line 515 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::recoverDatabase ( )
privateslot

Definition at line 1124 of file DatabaseViewer.cpp.

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

Definition at line 4034 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::refineAllLoopClosureLinks ( )
privateslot

Definition at line 4030 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::refineAllNeighborLinks ( )
privateslot

Definition at line 4026 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::refineConstraint ( )
privateslot

Definition at line 6950 of file DatabaseViewer.cpp.

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

Definition at line 6957 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::regenerateCurrentLocalMaps ( )
privateslot

Definition at line 3605 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::regenerateLocalMaps ( )
privateslot

Definition at line 3469 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::regenerateSavedMap ( )
privateslot

Definition at line 3001 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::rejectConstraint ( )
privateslot

Definition at line 7870 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::resetAllChanges ( )
privateslot

Definition at line 4066 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::resetConstraint ( )
privateslot

Definition at line 7842 of file DatabaseViewer.cpp.

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

Definition at line 1220 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::restoreDefaultSettings ( )
privateslot

Definition at line 696 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::selectEmptyColor ( )
privateslot

Definition at line 2181 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::selectGroundColor ( )
privateslot

Definition at line 2173 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::selectObstacleColor ( )
privateslot

Definition at line 2165 of file DatabaseViewer.cpp.

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

Definition at line 475 of file DatabaseViewer.cpp.

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

Definition at line 491 of file DatabaseViewer.cpp.

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

Definition at line 1197 of file DatabaseViewer.cpp.

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

Definition at line 5248 of file DatabaseViewer.cpp.

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

Definition at line 4085 of file DatabaseViewer.cpp.

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

Definition at line 5261 of file DatabaseViewer.cpp.

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

Definition at line 4107 of file DatabaseViewer.cpp.

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

Definition at line 6072 of file DatabaseViewer.cpp.

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

Definition at line 5297 of file DatabaseViewer.cpp.

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

Definition at line 5289 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 *  labelCalib,
QLabel *  labelScan,
QLabel *  labelGravity,
QLabel *  labelGps,
QLabel *  labelSensors,
bool  updateConstraintView 
)
private

Definition at line 4129 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::update3dView ( )
privateslot

Definition at line 5274 of file DatabaseViewer.cpp.

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

Definition at line 3952 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateAllLoopClosureCovariances ( )
privateslot

Definition at line 3947 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateAllNeighborCovariances ( )
privateslot

Definition at line 3943 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateConstraintButtons ( )
privateslot

Definition at line 6014 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateConstraintView ( )
privateslot

Definition at line 5388 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 5415 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateGraphView ( )
privateslot

Definition at line 6487 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateGrid ( )
privateslot

Definition at line 6792 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateIds ( )
private

Definition at line 1558 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateInfo ( )
privateslot

Definition at line 1987 of file DatabaseViewer.cpp.

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

Definition at line 7936 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateLoggerLevel ( )
privateslot

Definition at line 4964 of file DatabaseViewer.cpp.

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

Definition at line 7986 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateOctomapView ( )
privateslot

Definition at line 6814 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateOptimizedMesh ( )
privateslot

Definition at line 3237 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateStatistics ( )
privateslot

Definition at line 2113 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::updateStereo ( )
privateslot

Definition at line 4972 of file DatabaseViewer.cpp.

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

Definition at line 4984 of file DatabaseViewer.cpp.

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

Definition at line 5159 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::view3DMap ( )
privateslot

Definition at line 3716 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::viewOptimizedMesh ( )
privateslot

Definition at line 3070 of file DatabaseViewer.cpp.

void rtabmap::DatabaseViewer::writeSettings ( )
privateslot

Definition at line 603 of file DatabaseViewer.cpp.

Member Data Documentation

CloudViewer* rtabmap::DatabaseViewer::cloudViewer_
private

Definition at line 198 of file DatabaseViewer.h.

CloudViewer* rtabmap::DatabaseViewer::constraintsViewer_
private

Definition at line 197 of file DatabaseViewer.h.

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

Definition at line 212 of file DatabaseViewer.h.

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

Definition at line 210 of file DatabaseViewer.h.

EditDepthArea* rtabmap::DatabaseViewer::editDepthArea_
private

Definition at line 232 of file DatabaseViewer.h.

QDialog* rtabmap::DatabaseViewer::editDepthDialog_
private

Definition at line 231 of file DatabaseViewer.h.

EditMapArea* rtabmap::DatabaseViewer::editMapArea_
private

Definition at line 234 of file DatabaseViewer.h.

QDialog* rtabmap::DatabaseViewer::editMapDialog_
private

Definition at line 233 of file DatabaseViewer.h.

ExportCloudsDialog* rtabmap::DatabaseViewer::exportDialog_
private

Definition at line 230 of file DatabaseViewer.h.

bool rtabmap::DatabaseViewer::firstCall_
private

Definition at line 237 of file DatabaseViewer.h.

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

Definition at line 225 of file DatabaseViewer.h.

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

Definition at line 226 of file DatabaseViewer.h.

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

Definition at line 217 of file DatabaseViewer.h.

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

Definition at line 218 of file DatabaseViewer.h.

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

Definition at line 213 of file DatabaseViewer.h.

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

Definition at line 214 of file DatabaseViewer.h.

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

Definition at line 216 of file DatabaseViewer.h.

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

Definition at line 201 of file DatabaseViewer.h.

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

Definition at line 206 of file DatabaseViewer.h.

bool rtabmap::DatabaseViewer::infoReducedGraph_
private

Definition at line 240 of file DatabaseViewer.h.

int rtabmap::DatabaseViewer::infoSessions_
private

Definition at line 243 of file DatabaseViewer.h.

double rtabmap::DatabaseViewer::infoTotalOdom_
private

Definition at line 241 of file DatabaseViewer.h.

double rtabmap::DatabaseViewer::infoTotalTime_
private

Definition at line 242 of file DatabaseViewer.h.

QString rtabmap::DatabaseViewer::iniFilePath_
private

Definition at line 238 of file DatabaseViewer.h.

int rtabmap::DatabaseViewer::lastSliderIndexBrowsed_
private

Definition at line 209 of file DatabaseViewer.h.

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

Definition at line 202 of file DatabaseViewer.h.

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

Definition at line 219 of file DatabaseViewer.h.

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

Definition at line 221 of file DatabaseViewer.h.

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

Definition at line 220 of file DatabaseViewer.h.

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

Definition at line 222 of file DatabaseViewer.h.

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

Definition at line 223 of file DatabaseViewer.h.

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

Definition at line 224 of file DatabaseViewer.h.

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

Definition at line 208 of file DatabaseViewer.h.

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

Definition at line 203 of file DatabaseViewer.h.

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

Definition at line 227 of file DatabaseViewer.h.

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

Definition at line 207 of file DatabaseViewer.h.

CloudViewer* rtabmap::DatabaseViewer::occupancyGridViewer_
private

Definition at line 200 of file DatabaseViewer.h.

OctoMap* rtabmap::DatabaseViewer::octomap_
private

Definition at line 229 of file DatabaseViewer.h.

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

Definition at line 228 of file DatabaseViewer.h.

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

Definition at line 215 of file DatabaseViewer.h.

QString rtabmap::DatabaseViewer::pathDatabase_
private

Definition at line 211 of file DatabaseViewer.h.

bool rtabmap::DatabaseViewer::savedMaximized_
private

Definition at line 236 of file DatabaseViewer.h.

CloudViewer* rtabmap::DatabaseViewer::stereoViewer_
private

Definition at line 199 of file DatabaseViewer.h.

Ui_DatabaseViewer* rtabmap::DatabaseViewer::ui_
private

Definition at line 196 of file DatabaseViewer.h.

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

Definition at line 204 of file DatabaseViewer.h.

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

Definition at line 205 of file DatabaseViewer.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:08