Public Types | Public Slots | Signals | Public Member Functions | Protected Slots | Protected Member Functions | Private Member Functions | Private Attributes
rtabmap::MainWindow Class Reference

#include <MainWindow.h>

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

List of all members.

Public Types

enum  State {
  kIdle, kInitializing, kInitialized, kApplicationClosing,
  kClosing, kStartingDetection, kDetecting, kPaused,
  kMonitoring, kMonitoringPaused
}

Public Slots

void openDatabase (const QString &path, const rtabmap::ParametersMap &overridedParameters=rtabmap::ParametersMap())
virtual void processStats (const rtabmap::Statistics &stat)
void updateCacheFromDatabase (const QString &path)
void updateParameters (const rtabmap::ParametersMap &parameters)

Signals

void cameraInfoProcessed ()
void cameraInfoReceived (const rtabmap::CameraInfo &)
void detectionRateChanged (double)
void imgRateChanged (double)
void loopClosureThrChanged (float)
void mappingModeChanged (bool)
void noMoreImagesReceived ()
void odometryProcessed ()
void odometryReceived (const rtabmap::OdometryEvent &, bool)
void rtabmapEvent3DMapProcessed ()
void rtabmapEvent3DMapReceived (const rtabmap::RtabmapEvent3DMap &event)
void rtabmapEventInitReceived (int status, const QString &info)
void rtabmapGlobalPathEventReceived (const rtabmap::RtabmapGlobalPathEvent &event)
void rtabmapGoalStatusEventReceived (int status)
void rtabmapLabelErrorReceived (int id, const QString &label)
void stateChanged (MainWindow::State)
void statsProcessed ()
void statsReceived (const rtabmap::Statistics &)
void thresholdsChanged (int, int)
void timeLimitChanged (float)
void twistReceived (float x, float y, float z, float roll, float pitch, float yaw, int row, int col)

Public Member Functions

QString getWorkingDirectory () const
bool isDatabaseUpdated () const
bool isProcessingOdometry () const
bool isProcessingStatistics () const
bool isSavedMaximized () const
 MainWindow (PreferencesDialog *prefDialog=0, QWidget *parent=0, bool showSplashScreen=true)
void setMonitoringState (bool pauseChecked=false)
virtual ~MainWindow ()

Protected Slots

void anchorCloudsToGroundTruth ()
void applyPrefSettings (PreferencesDialog::PANEL_FLAGS flags)
void applyPrefSettings (const rtabmap::ParametersMap &parameters)
void beep ()
void cancelGoal ()
void cancelProgress ()
void changeDetectionRateSetting ()
void changeImgRateSetting ()
void changeMappingMode ()
virtual void changeState (MainWindow::State state)
void changeTimeLimitSetting ()
virtual void clearTheCache ()
virtual bool closeDatabase ()
void configGUIModified ()
void dataRecorder ()
void dataRecorderDestroyed ()
virtual void deleteMemory ()
void depthCalibration ()
virtual void downloadAllClouds ()
virtual void downloadPoseGraph ()
void dumpTheMemory ()
void dumpThePrediction ()
void editDatabase ()
void exportBundlerFormat ()
void exportClouds ()
void exportGridMap ()
void exportImages ()
void exportOctomap ()
void exportPosesG2O ()
void exportPosesKITTI ()
void exportPosesRaw ()
void exportPosesRGBDSLAM ()
void exportPosesTORO ()
void generateGraphDOT ()
void label ()
virtual void newDatabase ()
void notifyNoMoreImages ()
virtual void openDatabase ()
virtual void openHelp ()
virtual void openPreferences ()
virtual void openPreferencesSource ()
void openWorkingDirectory ()
virtual void pauseDetection ()
void postGoal (const QString &goal)
void postProcessing ()
void printLoopClosureIds ()
void processCameraInfo (const rtabmap::CameraInfo &info)
void processOdometry (const rtabmap::OdometryEvent &odom, bool dataIgnored)
void processRtabmapEvent3DMap (const rtabmap::RtabmapEvent3DMap &event)
void processRtabmapEventInit (int status, const QString &info)
void processRtabmapGlobalPathEvent (const rtabmap::RtabmapGlobalPathEvent &event)
void processRtabmapGoalStatusEvent (int status)
void processRtabmapLabelErrorEvent (int id, const QString &label)
virtual void resetOdometry ()
virtual void saveConfigGUI ()
void selectFreenect ()
void selectFreenect2 ()
void selectK4W2 ()
void selectOpenni ()
void selectOpenni2 ()
void selectOpenniCv ()
void selectOpenniCvAsus ()
void selectRealSense ()
void selectRealSense2 ()
void selectScreenCaptureFormat (bool checked)
void selectStereoDC1394 ()
void selectStereoFlyCapture2 ()
void selectStereoUsb ()
void selectStereoZed ()
void selectStream ()
void sendGoal ()
void sendWaypoints ()
void setAspectRatio (int w, int h)
void setAspectRatio1080p ()
void setAspectRatio16_10 ()
void setAspectRatio16_9 ()
void setAspectRatio240p ()
void setAspectRatio360p ()
void setAspectRatio480p ()
void setAspectRatio4_3 ()
void setAspectRatio720p ()
void setAspectRatioCustom ()
virtual void setDefaultViews ()
virtual void startDetection ()
virtual void stopDetection ()
void takeScreenshot ()
virtual void triggerNewMap ()
void updateCacheFromDatabase ()
void updateEditMenu ()
void updateElapsedTime ()
void updateGraphView ()
void updateNodeVisibility (int, bool)
void viewClouds ()

Protected Member Functions

const std::map< int, std::pair
< pcl::PointCloud
< pcl::PointXYZRGB >::Ptr,
pcl::IndicesPtr > > & 
cachedClouds () const
const QMap< int, Signature > & cachedSignatures () const
virtual void closeEvent (QCloseEvent *event)
rtabmap::CloudViewercloudViewer () const
const std::map< int,
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr > & 
createdFeatures () const
const std::map< int, LaserScan > & createdScans () const
const std::map< int, Transform > & currentGTPosesMap () const
const std::map< int,
std::string > & 
currentLabels () const
const std::multimap< int, Link > & currentLinksMap () const
const std::map< int, int > & currentMapIds () const
const std::map< int, Transform > & currentPosesMap () const
virtual bool eventFilter (QObject *obj, QEvent *event)
virtual bool handleEvent (UEvent *anEvent)
virtual void keyPressEvent (QKeyEvent *event)
rtabmap::LoopClosureViewerloopClosureViewer () const
virtual void moveEvent (QMoveEvent *anEvent)
const QString & newDatabasePathOutput () const
const rtabmap::OccupancyGridoccupancyGrid () const
const rtabmap::OctoMapoctomap () const
rtabmap::ProgressDialogprogressDialog ()
virtual void resizeEvent (QResizeEvent *anEvent)
void setCloudViewer (rtabmap::CloudViewer *cloudViewer)
void setLoopClosureViewer (rtabmap::LoopClosureViewer *loopClosureViewer)
void setNewDatabasePathOutput (const QString &newDatabasePathOutput)
virtual void showEvent (QShowEvent *anEvent)
const Statestate () const
Ui_mainWindow * ui ()

Private Member Functions

Transform alignPosesToGroundTruth (const std::map< int, Transform > &poses, const std::map< int, Transform > &groundTruth)
void applyPrefSettings (const rtabmap::ParametersMap &parameters, bool postParamEvent)
QString captureScreen (bool cacheInRAM=false, bool png=true)
std::pair< pcl::PointCloud
< pcl::PointXYZRGB >::Ptr,
pcl::IndicesPtr > 
createAndAddCloudToMap (int nodeId, const Transform &pose, int mapId)
void createAndAddFeaturesToMap (int nodeId, const Transform &pose, int mapId)
void createAndAddScanToMap (int nodeId, const Transform &pose, int mapId)
void drawKeypoints (const std::multimap< int, cv::KeyPoint > &refWords, const std::multimap< int, cv::KeyPoint > &loopWords)
void exportPoses (int format)
void loadFigures ()
void saveFigures ()
void setupMainLayout (bool vertical)
void update3DMapVisibility (bool cloudsShown, bool scansShown)
void updateMapCloud (const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints, const std::map< int, int > &mapIds, const std::map< int, std::string > &labels, const std::map< int, Transform > &groundTruths, bool verboseProgress=false, std::map< std::string, float > *stats=0)
void updateSelectSourceMenu ()

Private Attributes

AboutDialog_aboutDialog
QMap< QString, QByteArray > _autoScreenCaptureCachedImages
bool _autoScreenCaptureOdomSync
bool _autoScreenCapturePNG
bool _autoScreenCaptureRAM
std::map< int, std::pair
< pcl::PointCloud
< pcl::PointXYZRGB >::Ptr,
pcl::IndicesPtr > > 
_cachedClouds
std::set< int > _cachedEmptyClouds
std::map< int, float > _cachedLocalizationsCount
long _cachedMemoryUsage
QMap< int, Signature_cachedSignatures
std::map< int, float > _cachedWordsCount
rtabmap::CameraThread_camera
CloudViewer_cloudViewer
long _createdCloudsMemoryUsage
std::map< int, pcl::PointCloud
< pcl::PointXYZRGB >::Ptr > 
_createdFeatures
std::map< int, LaserScan_createdScans
std::map< int, Transform_currentGTPosesMap
std::map< int, std::string > _currentLabels
std::multimap< int, Link_currentLinksMap
std::map< int, int > _currentMapIds
std::map< int, Transform_currentPosesMap
bool _databaseUpdated
DataRecorder_dataRecorder
DepthCalibrationDialog_depthCalibrationDialog
QTime * _elapsedTime
ExportBundlerDialog_exportBundlerDialog
ExportCloudsDialog_exportCloudsDialog
QMap< int, QString > _exportPosesFileName
bool _exportPosesFrame
bool _firstCall
double _firstStamp
QString _graphSavingFileName
rtabmap::IMUThread_imuThread
int _lastId
QSet< int > _lastIds
Transform _lastOdomPose
PdfPlotCurve_likelihoodCurve
QTime * _logEventTime
QVector< int > _loopClosureIds
LoopClosureViewer_loopClosureViewer
QString _newDatabasePath
QString _newDatabasePathOutput
rtabmap::OccupancyGrid_occupancyGrid
rtabmap::OctoMap_octomap
Transform _odometryCorrection
bool _odometryReceived
bool _odomImageDepthShow
bool _odomImageShow
rtabmap::OdometryThread_odomThread
QTimer * _oneSecondTimer
QString _openedDatabasePath
PdfPlotCurve_posteriorCurve
PostProcessingDialog_postProcessingDialog
PreferencesDialog_preferencesDialog
std::pair< int, std::pair
< std::pair< pcl::PointCloud
< pcl::PointXYZRGB >::Ptr,
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr >, pcl::IndicesPtr > > 
_previousCloud
bool _processingDownloadedMap
bool _processingOdometry
bool _processingStatistics
bool _progressCanceled
ProgressDialog_progressDialog
PdfPlotCurve_rawLikelihoodCurve
bool _recovering
std::vector< CameraModel_rectCameraModels
QVector< int > _refIds
bool _savedMaximized
State _state
Ui_mainWindow * _ui
QStringList _waypoints
int _waypointsIndex

Detailed Description

Definition at line 77 of file MainWindow.h.


Member Enumeration Documentation

Enumerator:
kIdle 
kInitializing 
kInitialized 
kApplicationClosing 
kClosing 
kStartingDetection 
kDetecting 
kPaused 
kMonitoring 
kMonitoringPaused 

Definition at line 82 of file MainWindow.h.


Constructor & Destructor Documentation

rtabmap::MainWindow::MainWindow ( PreferencesDialog prefDialog = 0,
QWidget *  parent = 0,
bool  showSplashScreen = true 
)
Parameters:
prefDialogIf NULL, a default dialog is created. This dialog is automatically destroyed with the MainWindow.

Definition at line 134 of file MainWindow.cpp.

Definition at line 647 of file MainWindow.cpp.


Member Function Documentation

Transform rtabmap::MainWindow::alignPosesToGroundTruth ( const std::map< int, Transform > &  poses,
const std::map< int, Transform > &  groundTruth 
) [private]

Definition at line 3543 of file MainWindow.cpp.

Definition at line 6274 of file MainWindow.cpp.

void rtabmap::MainWindow::applyPrefSettings ( PreferencesDialog::PANEL_FLAGS  flags) [protected, slot]

Definition at line 3994 of file MainWindow.cpp.

void rtabmap::MainWindow::applyPrefSettings ( const rtabmap::ParametersMap parameters) [protected, slot]

Definition at line 4055 of file MainWindow.cpp.

void rtabmap::MainWindow::applyPrefSettings ( const rtabmap::ParametersMap parameters,
bool  postParamEvent 
) [private]

Definition at line 4060 of file MainWindow.cpp.

void rtabmap::MainWindow::beep ( ) [protected, slot]

Definition at line 4408 of file MainWindow.cpp.

const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> >& rtabmap::MainWindow::cachedClouds ( ) const [inline, protected]

Definition at line 280 of file MainWindow.h.

const QMap<int, Signature>& rtabmap::MainWindow::cachedSignatures ( ) const [inline, protected]

Definition at line 274 of file MainWindow.h.

void rtabmap::MainWindow::cancelGoal ( ) [protected, slot]

Definition at line 6121 of file MainWindow.cpp.

void rtabmap::MainWindow::cancelProgress ( ) [protected, slot]

Definition at line 4413 of file MainWindow.cpp.

QString rtabmap::MainWindow::captureScreen ( bool  cacheInRAM = false,
bool  png = true 
) [private]

Definition at line 4367 of file MainWindow.cpp.

Definition at line 4352 of file MainWindow.cpp.

void rtabmap::MainWindow::changeImgRateSetting ( ) [protected, slot]

Definition at line 4347 of file MainWindow.cpp.

void rtabmap::MainWindow::changeMappingMode ( ) [protected, slot]

Definition at line 4362 of file MainWindow.cpp.

void rtabmap::MainWindow::changeState ( MainWindow::State  state) [protected, virtual, slot]

Definition at line 7271 of file MainWindow.cpp.

void rtabmap::MainWindow::changeTimeLimitSetting ( ) [protected, slot]

Definition at line 4357 of file MainWindow.cpp.

void rtabmap::MainWindow::clearTheCache ( ) [protected, virtual, slot]

Definition at line 6284 of file MainWindow.cpp.

bool rtabmap::MainWindow::closeDatabase ( ) [protected, virtual, slot]

Definition at line 4655 of file MainWindow.cpp.

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

Definition at line 696 of file MainWindow.cpp.

Definition at line 288 of file MainWindow.h.

void rtabmap::MainWindow::configGUIModified ( ) [protected, slot]

Definition at line 4419 of file MainWindow.cpp.

std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > rtabmap::MainWindow::createAndAddCloudToMap ( int  nodeId,
const Transform pose,
int  mapId 
) [private]

Definition at line 2758 of file MainWindow.cpp.

void rtabmap::MainWindow::createAndAddFeaturesToMap ( int  nodeId,
const Transform pose,
int  mapId 
) [private]

Definition at line 3444 of file MainWindow.cpp.

void rtabmap::MainWindow::createAndAddScanToMap ( int  nodeId,
const Transform pose,
int  mapId 
) [private]

Definition at line 3133 of file MainWindow.cpp.

const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& rtabmap::MainWindow::createdFeatures ( ) const [inline, protected]

Definition at line 282 of file MainWindow.h.

const std::map<int, LaserScan>& rtabmap::MainWindow::createdScans ( ) const [inline, protected]

Definition at line 281 of file MainWindow.h.

const std::map<int, Transform>& rtabmap::MainWindow::currentGTPosesMap ( ) const [inline, protected]

Definition at line 276 of file MainWindow.h.

const std::map<int, std::string>& rtabmap::MainWindow::currentLabels ( ) const [inline, protected]

Definition at line 279 of file MainWindow.h.

const std::multimap<int, Link>& rtabmap::MainWindow::currentLinksMap ( ) const [inline, protected]

Definition at line 277 of file MainWindow.h.

const std::map<int, int>& rtabmap::MainWindow::currentMapIds ( ) const [inline, protected]

Definition at line 278 of file MainWindow.h.

const std::map<int, Transform>& rtabmap::MainWindow::currentPosesMap ( ) const [inline, protected]

Definition at line 275 of file MainWindow.h.

void rtabmap::MainWindow::dataRecorder ( ) [protected, slot]

Definition at line 7209 of file MainWindow.cpp.

void rtabmap::MainWindow::dataRecorderDestroyed ( ) [protected, slot]

Definition at line 7254 of file MainWindow.cpp.

void rtabmap::MainWindow::deleteMemory ( ) [protected, virtual, slot]

Definition at line 5911 of file MainWindow.cpp.

void rtabmap::MainWindow::depthCalibration ( ) [protected, slot]

Definition at line 5895 of file MainWindow.cpp.

void rtabmap::MainWindow::detectionRateChanged ( double  ) [signal]
void rtabmap::MainWindow::downloadAllClouds ( ) [protected, virtual, slot]

Definition at line 6185 of file MainWindow.cpp.

void rtabmap::MainWindow::downloadPoseGraph ( ) [protected, virtual, slot]

Definition at line 6229 of file MainWindow.cpp.

void rtabmap::MainWindow::drawKeypoints ( const std::multimap< int, cv::KeyPoint > &  refWords,
const std::multimap< int, cv::KeyPoint > &  loopWords 
) [private]

Definition at line 4109 of file MainWindow.cpp.

void rtabmap::MainWindow::dumpTheMemory ( ) [protected, slot]

Definition at line 6057 of file MainWindow.cpp.

void rtabmap::MainWindow::dumpThePrediction ( ) [protected, slot]

Definition at line 6062 of file MainWindow.cpp.

void rtabmap::MainWindow::editDatabase ( ) [protected, slot]

Definition at line 4701 of file MainWindow.cpp.

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

Definition at line 4301 of file MainWindow.cpp.

void rtabmap::MainWindow::exportBundlerFormat ( ) [protected, slot]

Definition at line 6976 of file MainWindow.cpp.

void rtabmap::MainWindow::exportClouds ( ) [protected, slot]

Definition at line 6696 of file MainWindow.cpp.

void rtabmap::MainWindow::exportGridMap ( ) [protected, slot]

Definition at line 6626 of file MainWindow.cpp.

void rtabmap::MainWindow::exportImages ( ) [protected, slot]

Definition at line 6809 of file MainWindow.cpp.

void rtabmap::MainWindow::exportOctomap ( ) [protected, slot]

Definition at line 6771 of file MainWindow.cpp.

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

Definition at line 5182 of file MainWindow.cpp.

void rtabmap::MainWindow::exportPosesG2O ( ) [protected, slot]

Definition at line 5177 of file MainWindow.cpp.

void rtabmap::MainWindow::exportPosesKITTI ( ) [protected, slot]

Definition at line 5169 of file MainWindow.cpp.

void rtabmap::MainWindow::exportPosesRaw ( ) [protected, slot]

Definition at line 5161 of file MainWindow.cpp.

void rtabmap::MainWindow::exportPosesRGBDSLAM ( ) [protected, slot]

Definition at line 5165 of file MainWindow.cpp.

void rtabmap::MainWindow::exportPosesTORO ( ) [protected, slot]

Definition at line 5173 of file MainWindow.cpp.

void rtabmap::MainWindow::generateGraphDOT ( ) [protected, slot]

Definition at line 5129 of file MainWindow.cpp.

Definition at line 5944 of file MainWindow.cpp.

bool rtabmap::MainWindow::handleEvent ( UEvent event) [protected, virtual]

Method called by the UEventsManager to handle an event. Important : this method must do a minimum of work because the faster the dispatching loop is done; the faster the events are received. If a handling function takes too much time, the events list can grow faster than it is emptied. The event can be modified.

Returns:
"true" to notify UEventsManager that this handler took ownership of the event (meaning it must delete it). The event will not be dispatched to next handlers.
"false" to let event be dispatched to next handlers (default behavior). UEventsManager will take care of deleting the event.

Implements UEventsHandler.

Definition at line 790 of file MainWindow.cpp.

void rtabmap::MainWindow::imgRateChanged ( double  ) [signal]
bool rtabmap::MainWindow::isDatabaseUpdated ( ) const [inline]

Definition at line 110 of file MainWindow.h.

Definition at line 108 of file MainWindow.h.

Definition at line 107 of file MainWindow.h.

bool rtabmap::MainWindow::isSavedMaximized ( ) const [inline]

Definition at line 105 of file MainWindow.h.

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

Definition at line 4292 of file MainWindow.cpp.

void rtabmap::MainWindow::label ( ) [protected, slot]

Definition at line 6129 of file MainWindow.cpp.

Definition at line 6390 of file MainWindow.cpp.

void rtabmap::MainWindow::loopClosureThrChanged ( float  ) [signal]

Definition at line 289 of file MainWindow.h.

void rtabmap::MainWindow::mappingModeChanged ( bool  ) [signal]
void rtabmap::MainWindow::moveEvent ( QMoveEvent *  anEvent) [protected, virtual]

Definition at line 4271 of file MainWindow.cpp.

void rtabmap::MainWindow::newDatabase ( ) [protected, virtual, slot]

Definition at line 4467 of file MainWindow.cpp.

const QString& rtabmap::MainWindow::newDatabasePathOutput ( ) const [inline, protected]

Definition at line 295 of file MainWindow.h.

void rtabmap::MainWindow::notifyNoMoreImages ( ) [protected, slot]

Definition at line 5103 of file MainWindow.cpp.

const rtabmap::OccupancyGrid* rtabmap::MainWindow::occupancyGrid ( ) const [inline, protected]

Definition at line 284 of file MainWindow.h.

const rtabmap::OctoMap* rtabmap::MainWindow::octomap ( ) const [inline, protected]

Definition at line 285 of file MainWindow.h.

void rtabmap::MainWindow::odometryReceived ( const rtabmap::OdometryEvent ,
bool   
) [signal]
void rtabmap::MainWindow::openDatabase ( const QString &  path,
const rtabmap::ParametersMap overridedParameters = rtabmap::ParametersMap() 
) [slot]

Definition at line 4560 of file MainWindow.cpp.

void rtabmap::MainWindow::openDatabase ( ) [protected, virtual, slot]

Definition at line 4551 of file MainWindow.cpp.

void rtabmap::MainWindow::openHelp ( ) [protected, virtual, slot]

Definition at line 6350 of file MainWindow.cpp.

void rtabmap::MainWindow::openPreferences ( ) [protected, virtual, slot]

Definition at line 6423 of file MainWindow.cpp.

void rtabmap::MainWindow::openPreferencesSource ( ) [protected, virtual, slot]

Definition at line 6429 of file MainWindow.cpp.

void rtabmap::MainWindow::openWorkingDirectory ( ) [protected, slot]

Definition at line 5949 of file MainWindow.cpp.

void rtabmap::MainWindow::pauseDetection ( ) [protected, virtual, slot]

Definition at line 5007 of file MainWindow.cpp.

void rtabmap::MainWindow::postGoal ( const QString &  goal) [protected, slot]

Definition at line 6102 of file MainWindow.cpp.

void rtabmap::MainWindow::postProcessing ( ) [protected, slot]

Definition at line 5359 of file MainWindow.cpp.

void rtabmap::MainWindow::printLoopClosureIds ( ) [protected, slot]

Definition at line 5110 of file MainWindow.cpp.

void rtabmap::MainWindow::processCameraInfo ( const rtabmap::CameraInfo info) [protected, slot]

Definition at line 926 of file MainWindow.cpp.

void rtabmap::MainWindow::processOdometry ( const rtabmap::OdometryEvent odom,
bool  dataIgnored 
) [protected, slot]

Definition at line 945 of file MainWindow.cpp.

Definition at line 3798 of file MainWindow.cpp.

void rtabmap::MainWindow::processRtabmapEventInit ( int  status,
const QString &  info 
) [protected, slot]

Definition at line 3672 of file MainWindow.cpp.

Definition at line 3912 of file MainWindow.cpp.

void rtabmap::MainWindow::processRtabmapGoalStatusEvent ( int  status) [protected, slot]

Definition at line 3985 of file MainWindow.cpp.

void rtabmap::MainWindow::processRtabmapLabelErrorEvent ( int  id,
const QString &  label 
) [protected, slot]

Definition at line 3970 of file MainWindow.cpp.

void rtabmap::MainWindow::processStats ( const rtabmap::Statistics stat) [virtual, slot]

Definition at line 1534 of file MainWindow.cpp.

Definition at line 287 of file MainWindow.h.

void rtabmap::MainWindow::resetOdometry ( ) [protected, virtual, slot]

Definition at line 7197 of file MainWindow.cpp.

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

Definition at line 4284 of file MainWindow.cpp.

void rtabmap::MainWindow::rtabmapEventInitReceived ( int  status,
const QString &  info 
) [signal]
void rtabmap::MainWindow::rtabmapLabelErrorReceived ( int  id,
const QString &  label 
) [signal]
void rtabmap::MainWindow::saveConfigGUI ( ) [protected, virtual, slot]

Definition at line 4447 of file MainWindow.cpp.

Definition at line 6371 of file MainWindow.cpp.

void rtabmap::MainWindow::selectFreenect ( ) [protected, slot]

Definition at line 5998 of file MainWindow.cpp.

void rtabmap::MainWindow::selectFreenect2 ( ) [protected, slot]

Definition at line 6018 of file MainWindow.cpp.

void rtabmap::MainWindow::selectK4W2 ( ) [protected, slot]

Definition at line 6023 of file MainWindow.cpp.

void rtabmap::MainWindow::selectOpenni ( ) [protected, slot]

Definition at line 5993 of file MainWindow.cpp.

void rtabmap::MainWindow::selectOpenni2 ( ) [protected, slot]

Definition at line 6013 of file MainWindow.cpp.

void rtabmap::MainWindow::selectOpenniCv ( ) [protected, slot]

Definition at line 6003 of file MainWindow.cpp.

void rtabmap::MainWindow::selectOpenniCvAsus ( ) [protected, slot]

Definition at line 6008 of file MainWindow.cpp.

void rtabmap::MainWindow::selectRealSense ( ) [protected, slot]

Definition at line 6028 of file MainWindow.cpp.

void rtabmap::MainWindow::selectRealSense2 ( ) [protected, slot]

Definition at line 6033 of file MainWindow.cpp.

void rtabmap::MainWindow::selectScreenCaptureFormat ( bool  checked) [protected, slot]

Definition at line 6458 of file MainWindow.cpp.

void rtabmap::MainWindow::selectStereoDC1394 ( ) [protected, slot]

Definition at line 6038 of file MainWindow.cpp.

Definition at line 6043 of file MainWindow.cpp.

void rtabmap::MainWindow::selectStereoUsb ( ) [protected, slot]

Definition at line 6052 of file MainWindow.cpp.

void rtabmap::MainWindow::selectStereoZed ( ) [protected, slot]

Definition at line 6047 of file MainWindow.cpp.

void rtabmap::MainWindow::selectStream ( ) [protected, slot]

Definition at line 5988 of file MainWindow.cpp.

void rtabmap::MainWindow::sendGoal ( ) [protected, slot]

Definition at line 6067 of file MainWindow.cpp.

void rtabmap::MainWindow::sendWaypoints ( ) [protected, slot]

Definition at line 6081 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio ( int  w,
int  h 
) [protected, slot]

Definition at line 6546 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio1080p ( ) [protected, slot]

Definition at line 6607 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio16_10 ( ) [protected, slot]

Definition at line 6577 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio16_9 ( ) [protected, slot]

Definition at line 6572 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio240p ( ) [protected, slot]

Definition at line 6587 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio360p ( ) [protected, slot]

Definition at line 6592 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio480p ( ) [protected, slot]

Definition at line 6597 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio4_3 ( ) [protected, slot]

Definition at line 6582 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatio720p ( ) [protected, slot]

Definition at line 6602 of file MainWindow.cpp.

void rtabmap::MainWindow::setAspectRatioCustom ( ) [protected, slot]

Definition at line 6612 of file MainWindow.cpp.

void rtabmap::MainWindow::setCloudViewer ( rtabmap::CloudViewer cloudViewer) [protected]

Definition at line 672 of file MainWindow.cpp.

void rtabmap::MainWindow::setDefaultViews ( ) [protected, virtual, slot]

Definition at line 6436 of file MainWindow.cpp.

void rtabmap::MainWindow::setLoopClosureViewer ( rtabmap::LoopClosureViewer loopClosureViewer) [protected]

Definition at line 686 of file MainWindow.cpp.

void rtabmap::MainWindow::setMonitoringState ( bool  pauseChecked = false)

Definition at line 7265 of file MainWindow.cpp.

void rtabmap::MainWindow::setNewDatabasePathOutput ( const QString &  newDatabasePathOutput) [inline, protected]

Definition at line 294 of file MainWindow.h.

void rtabmap::MainWindow::setupMainLayout ( bool  vertical) [private]

Definition at line 660 of file MainWindow.cpp.

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

Definition at line 4265 of file MainWindow.cpp.

void rtabmap::MainWindow::startDetection ( ) [protected, virtual, slot]

Definition at line 4744 of file MainWindow.cpp.

const State& rtabmap::MainWindow::state ( ) const [inline, protected]

Definition at line 272 of file MainWindow.h.

void rtabmap::MainWindow::stopDetection ( ) [protected, virtual, slot]

Definition at line 5041 of file MainWindow.cpp.

void rtabmap::MainWindow::takeScreenshot ( ) [protected, slot]

Definition at line 6541 of file MainWindow.cpp.

void rtabmap::MainWindow::thresholdsChanged ( int  ,
int   
) [signal]
void rtabmap::MainWindow::timeLimitChanged ( float  ) [signal]
void rtabmap::MainWindow::triggerNewMap ( ) [protected, virtual, slot]

Definition at line 7203 of file MainWindow.cpp.

void rtabmap::MainWindow::twistReceived ( float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw,
int  row,
int  col 
) [signal]
Ui_mainWindow* rtabmap::MainWindow::ui ( ) [inline, protected]

Definition at line 271 of file MainWindow.h.

void rtabmap::MainWindow::update3DMapVisibility ( bool  cloudsShown,
bool  scansShown 
) [private]
void rtabmap::MainWindow::updateCacheFromDatabase ( const QString &  path) [slot]

Definition at line 6150 of file MainWindow.cpp.

Definition at line 6140 of file MainWindow.cpp.

void rtabmap::MainWindow::updateEditMenu ( ) [protected, slot]

Definition at line 5972 of file MainWindow.cpp.

void rtabmap::MainWindow::updateElapsedTime ( ) [protected, slot]

Definition at line 6362 of file MainWindow.cpp.

void rtabmap::MainWindow::updateGraphView ( ) [protected, slot]

Definition at line 3655 of file MainWindow.cpp.

void rtabmap::MainWindow::updateMapCloud ( const std::map< int, Transform > &  poses,
const std::multimap< int, Link > &  constraints,
const std::map< int, int > &  mapIds,
const std::map< int, std::string > &  labels,
const std::map< int, Transform > &  groundTruths,
bool  verboseProgress = false,
std::map< std::string, float > *  stats = 0 
) [private]

Definition at line 2048 of file MainWindow.cpp.

void rtabmap::MainWindow::updateNodeVisibility ( int  nodeId,
bool  visible 
) [protected, slot]

Definition at line 3597 of file MainWindow.cpp.

Definition at line 4424 of file MainWindow.cpp.

Definition at line 4314 of file MainWindow.cpp.

void rtabmap::MainWindow::viewClouds ( ) [protected, slot]

Definition at line 6733 of file MainWindow.cpp.


Member Data Documentation

Definition at line 307 of file MainWindow.h.

QMap<QString, QByteArray> rtabmap::MainWindow::_autoScreenCaptureCachedImages [private]

Definition at line 376 of file MainWindow.h.

Definition at line 373 of file MainWindow.h.

Definition at line 375 of file MainWindow.h.

Definition at line 374 of file MainWindow.h.

std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > rtabmap::MainWindow::_cachedClouds [private]

Definition at line 339 of file MainWindow.h.

std::set<int> rtabmap::MainWindow::_cachedEmptyClouds [private]

Definition at line 341 of file MainWindow.h.

std::map<int, float> rtabmap::MainWindow::_cachedLocalizationsCount [private]

Definition at line 344 of file MainWindow.h.

Definition at line 333 of file MainWindow.h.

Definition at line 332 of file MainWindow.h.

std::map<int, float> rtabmap::MainWindow::_cachedWordsCount [private]

Definition at line 343 of file MainWindow.h.

Definition at line 301 of file MainWindow.h.

Definition at line 367 of file MainWindow.h.

Definition at line 340 of file MainWindow.h.

std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> rtabmap::MainWindow::_createdFeatures [private]

Definition at line 351 of file MainWindow.h.

Definition at line 346 of file MainWindow.h.

Definition at line 335 of file MainWindow.h.

std::map<int, std::string> rtabmap::MainWindow::_currentLabels [private]

Definition at line 338 of file MainWindow.h.

std::multimap<int, Link> rtabmap::MainWindow::_currentLinksMap [private]

Definition at line 336 of file MainWindow.h.

std::map<int, int> rtabmap::MainWindow::_currentMapIds [private]

Definition at line 337 of file MainWindow.h.

Definition at line 334 of file MainWindow.h.

Definition at line 324 of file MainWindow.h.

Definition at line 312 of file MainWindow.h.

Definition at line 311 of file MainWindow.h.

Definition at line 358 of file MainWindow.h.

Definition at line 309 of file MainWindow.h.

Definition at line 308 of file MainWindow.h.

QMap<int, QString> rtabmap::MainWindow::_exportPosesFileName [private]

Definition at line 372 of file MainWindow.h.

Definition at line 371 of file MainWindow.h.

Definition at line 381 of file MainWindow.h.

Definition at line 316 of file MainWindow.h.

Definition at line 370 of file MainWindow.h.

Definition at line 303 of file MainWindow.h.

Definition at line 315 of file MainWindow.h.

QSet<int> rtabmap::MainWindow::_lastIds [private]

Definition at line 314 of file MainWindow.h.

Definition at line 354 of file MainWindow.h.

Definition at line 362 of file MainWindow.h.

Definition at line 359 of file MainWindow.h.

QVector<int> rtabmap::MainWindow::_loopClosureIds [private]

Definition at line 379 of file MainWindow.h.

Definition at line 368 of file MainWindow.h.

Definition at line 321 of file MainWindow.h.

Definition at line 322 of file MainWindow.h.

Definition at line 348 of file MainWindow.h.

Definition at line 349 of file MainWindow.h.

Definition at line 353 of file MainWindow.h.

Definition at line 320 of file MainWindow.h.

Definition at line 326 of file MainWindow.h.

Definition at line 325 of file MainWindow.h.

Definition at line 302 of file MainWindow.h.

Definition at line 357 of file MainWindow.h.

Definition at line 323 of file MainWindow.h.

Definition at line 361 of file MainWindow.h.

Definition at line 310 of file MainWindow.h.

Definition at line 306 of file MainWindow.h.

std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> > rtabmap::MainWindow::_previousCloud [private]

Definition at line 342 of file MainWindow.h.

Definition at line 318 of file MainWindow.h.

Definition at line 355 of file MainWindow.h.

Definition at line 317 of file MainWindow.h.

Definition at line 382 of file MainWindow.h.

Definition at line 365 of file MainWindow.h.

Definition at line 363 of file MainWindow.h.

Definition at line 319 of file MainWindow.h.

Definition at line 330 of file MainWindow.h.

QVector<int> rtabmap::MainWindow::_refIds [private]

Definition at line 378 of file MainWindow.h.

Definition at line 327 of file MainWindow.h.

Definition at line 300 of file MainWindow.h.

Ui_mainWindow* rtabmap::MainWindow::_ui [private]

Definition at line 298 of file MainWindow.h.

QStringList rtabmap::MainWindow::_waypoints [private]

Definition at line 328 of file MainWindow.h.

Definition at line 329 of file MainWindow.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