#include <MainWindow.h>
|
| void | cameraInfoProcessed () |
| |
| void | cameraInfoReceived (const rtabmap::CameraInfo &) |
| |
| void | detectionRateChanged (double) |
| |
| void | imgRateChanged (double) |
| |
| void | loopClosureThrChanged (qreal) |
| |
| 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) |
| |
|
| 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::CloudViewer * | cloudViewer () const |
| |
| virtual Camera * | createCamera () |
| |
| 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 ParametersMap | getCustomParameters () |
| |
| virtual bool | handleEvent (UEvent *anEvent) |
| |
| virtual void | keyPressEvent (QKeyEvent *event) |
| |
| rtabmap::LoopClosureViewer * | loopClosureViewer () const |
| |
| virtual void | moveEvent (QMoveEvent *anEvent) |
| |
| const QString & | newDatabasePathOutput () const |
| |
| const rtabmap::OccupancyGrid * | occupancyGrid () const |
| |
| const rtabmap::OctoMap * | octomap () const |
| |
| rtabmap::ProgressDialog * | progressDialog () |
| |
| 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 State & | state () const |
| |
| Ui_mainWindow * | ui () |
| |
Protected Member Functions inherited from UEventsHandler |
| | UEventsHandler () |
| |
| virtual | ~UEventsHandler () |
| |
| void | post (UEvent *event, bool async=true) const |
| |
|
| Transform | alignPosesToGroundTruth (const std::map< int, Transform > &poses, const std::map< int, Transform > &groundTruth) |
| |
| void | applyPrefSettings (const rtabmap::ParametersMap ¶meters, 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 | drawLandmarks (cv::Mat &image, const Signature &signature) |
| |
| 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 () |
| |
|
| 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 |
| |
| QString | _defaultOpenDatabasePath |
| |
| DepthCalibrationDialog * | _depthCalibrationDialog |
| |
| QTime * | _elapsedTime |
| |
| ExportBundlerDialog * | _exportBundlerDialog |
| |
| ExportCloudsDialog * | _exportCloudsDialog |
| |
| QMap< int, QString > | _exportPosesFileName |
| |
| int | _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 |
| |
Definition at line 77 of file MainWindow.h.
| Enumerator |
|---|
| kIdle |
|
| kInitializing |
|
| kInitialized |
|
| kApplicationClosing |
|
| kClosing |
|
| kStartingDetection |
|
| kDetecting |
|
| kPaused |
|
| kMonitoring |
|
| kMonitoringPaused |
|
Definition at line 82 of file MainWindow.h.
| rtabmap::MainWindow::MainWindow |
( |
PreferencesDialog * |
prefDialog = 0, |
|
|
QWidget * |
parent = 0, |
|
|
bool |
showSplashScreen = true |
|
) |
| |
- Parameters
-
| prefDialog | If NULL, a default dialog is created. This dialog is automatically destroyed with the MainWindow. |
Definition at line 137 of file MainWindow.cpp.
| rtabmap::MainWindow::~MainWindow |
( |
| ) |
|
|
virtual |
| Transform rtabmap::MainWindow::alignPosesToGroundTruth |
( |
const std::map< int, Transform > & |
poses, |
|
|
const std::map< int, Transform > & |
groundTruth |
|
) |
| |
|
private |
| void rtabmap::MainWindow::anchorCloudsToGroundTruth |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::applyPrefSettings |
( |
PreferencesDialog::PANEL_FLAGS |
flags | ) |
|
|
protectedslot |
| void rtabmap::MainWindow::applyPrefSettings |
( |
const rtabmap::ParametersMap & |
parameters, |
|
|
bool |
postParamEvent |
|
) |
| |
|
private |
| void rtabmap::MainWindow::beep |
( |
| ) |
|
|
protectedslot |
| const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> >& rtabmap::MainWindow::cachedClouds |
( |
| ) |
const |
|
inlineprotected |
| const QMap<int, Signature>& rtabmap::MainWindow::cachedSignatures |
( |
| ) |
const |
|
inlineprotected |
| void rtabmap::MainWindow::cameraInfoProcessed |
( |
| ) |
|
|
signal |
| void rtabmap::MainWindow::cancelGoal |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::cancelProgress |
( |
| ) |
|
|
protectedslot |
| QString rtabmap::MainWindow::captureScreen |
( |
bool |
cacheInRAM = false, |
|
|
bool |
png = true |
|
) |
| |
|
private |
| void rtabmap::MainWindow::changeDetectionRateSetting |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::changeImgRateSetting |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::changeMappingMode |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::changeTimeLimitSetting |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::clearTheCache |
( |
| ) |
|
|
protectedvirtualslot |
| bool rtabmap::MainWindow::closeDatabase |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::closeEvent |
( |
QCloseEvent * |
event | ) |
|
|
protectedvirtual |
| void rtabmap::MainWindow::configGUIModified |
( |
| ) |
|
|
protectedslot |
| std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > rtabmap::MainWindow::createAndAddCloudToMap |
( |
int |
nodeId, |
|
|
const Transform & |
pose, |
|
|
int |
mapId |
|
) |
| |
|
private |
| void rtabmap::MainWindow::createAndAddFeaturesToMap |
( |
int |
nodeId, |
|
|
const Transform & |
pose, |
|
|
int |
mapId |
|
) |
| |
|
private |
| void rtabmap::MainWindow::createAndAddScanToMap |
( |
int |
nodeId, |
|
|
const Transform & |
pose, |
|
|
int |
mapId |
|
) |
| |
|
private |
| Camera * rtabmap::MainWindow::createCamera |
( |
| ) |
|
|
protectedvirtual |
| const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& rtabmap::MainWindow::createdFeatures |
( |
| ) |
const |
|
inlineprotected |
| const std::map<int, LaserScan>& rtabmap::MainWindow::createdScans |
( |
| ) |
const |
|
inlineprotected |
| const std::map<int, Transform>& rtabmap::MainWindow::currentGTPosesMap |
( |
| ) |
const |
|
inlineprotected |
| const std::map<int, std::string>& rtabmap::MainWindow::currentLabels |
( |
| ) |
const |
|
inlineprotected |
| const std::multimap<int, Link>& rtabmap::MainWindow::currentLinksMap |
( |
| ) |
const |
|
inlineprotected |
| const std::map<int, int>& rtabmap::MainWindow::currentMapIds |
( |
| ) |
const |
|
inlineprotected |
| const std::map<int, Transform>& rtabmap::MainWindow::currentPosesMap |
( |
| ) |
const |
|
inlineprotected |
| void rtabmap::MainWindow::dataRecorder |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::dataRecorderDestroyed |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::deleteMemory |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::depthCalibration |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::detectionRateChanged |
( |
double |
| ) |
|
|
signal |
| void rtabmap::MainWindow::downloadAllClouds |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::downloadPoseGraph |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::drawKeypoints |
( |
const std::multimap< int, cv::KeyPoint > & |
refWords, |
|
|
const std::multimap< int, cv::KeyPoint > & |
loopWords |
|
) |
| |
|
private |
| void rtabmap::MainWindow::drawLandmarks |
( |
cv::Mat & |
image, |
|
|
const Signature & |
signature |
|
) |
| |
|
private |
| void rtabmap::MainWindow::dumpTheMemory |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::dumpThePrediction |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::editDatabase |
( |
| ) |
|
|
protectedslot |
| bool rtabmap::MainWindow::eventFilter |
( |
QObject * |
obj, |
|
|
QEvent * |
event |
|
) |
| |
|
protectedvirtual |
| void rtabmap::MainWindow::exportBundlerFormat |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportClouds |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportGridMap |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportImages |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportOctomap |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPoses |
( |
int |
format | ) |
|
|
private |
| void rtabmap::MainWindow::exportPosesG2O |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPosesKITTI |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPosesRaw |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPosesRGBDSLAM |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPosesRGBDSLAMMotionCapture |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::exportPosesTORO |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::generateGraphDOT |
( |
| ) |
|
|
protectedslot |
| virtual ParametersMap rtabmap::MainWindow::getCustomParameters |
( |
| ) |
|
|
inlineprotectedvirtual |
| QString rtabmap::MainWindow::getWorkingDirectory |
( |
| ) |
const |
| bool rtabmap::MainWindow::handleEvent |
( |
UEvent * |
event | ) |
|
|
protectedvirtual |
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 818 of file MainWindow.cpp.
| void rtabmap::MainWindow::imgRateChanged |
( |
double |
| ) |
|
|
signal |
| bool rtabmap::MainWindow::isDatabaseUpdated |
( |
| ) |
const |
|
inline |
| bool rtabmap::MainWindow::isProcessingOdometry |
( |
| ) |
const |
|
inline |
| bool rtabmap::MainWindow::isProcessingStatistics |
( |
| ) |
const |
|
inline |
| bool rtabmap::MainWindow::isSavedMaximized |
( |
| ) |
const |
|
inline |
| void rtabmap::MainWindow::keyPressEvent |
( |
QKeyEvent * |
event | ) |
|
|
protectedvirtual |
| void rtabmap::MainWindow::label |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::loadFigures |
( |
| ) |
|
|
private |
| void rtabmap::MainWindow::loopClosureThrChanged |
( |
qreal |
| ) |
|
|
signal |
| void rtabmap::MainWindow::mappingModeChanged |
( |
bool |
| ) |
|
|
signal |
| void rtabmap::MainWindow::moveEvent |
( |
QMoveEvent * |
anEvent | ) |
|
|
protectedvirtual |
| void rtabmap::MainWindow::newDatabase |
( |
| ) |
|
|
protectedvirtualslot |
| const QString& rtabmap::MainWindow::newDatabasePathOutput |
( |
| ) |
const |
|
inlineprotected |
| void rtabmap::MainWindow::noMoreImagesReceived |
( |
| ) |
|
|
signal |
| void rtabmap::MainWindow::notifyNoMoreImages |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::odometryProcessed |
( |
| ) |
|
|
signal |
| void rtabmap::MainWindow::openDatabase |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::openHelp |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::openPreferences |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::openPreferencesSource |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::openWorkingDirectory |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::pauseDetection |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::postGoal |
( |
const QString & |
goal | ) |
|
|
protectedslot |
| void rtabmap::MainWindow::postProcessing |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::printLoopClosureIds |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::processRtabmapEventInit |
( |
int |
status, |
|
|
const QString & |
info |
|
) |
| |
|
protectedslot |
| void rtabmap::MainWindow::processRtabmapGoalStatusEvent |
( |
int |
status | ) |
|
|
protectedslot |
| void rtabmap::MainWindow::processRtabmapLabelErrorEvent |
( |
int |
id, |
|
|
const QString & |
label |
|
) |
| |
|
protectedslot |
| void rtabmap::MainWindow::resetOdometry |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::resizeEvent |
( |
QResizeEvent * |
anEvent | ) |
|
|
protectedvirtual |
| void rtabmap::MainWindow::rtabmapEvent3DMapProcessed |
( |
| ) |
|
|
signal |
| void rtabmap::MainWindow::rtabmapEventInitReceived |
( |
int |
status, |
|
|
const QString & |
info |
|
) |
| |
|
signal |
| void rtabmap::MainWindow::rtabmapGoalStatusEventReceived |
( |
int |
status | ) |
|
|
signal |
| void rtabmap::MainWindow::rtabmapLabelErrorReceived |
( |
int |
id, |
|
|
const QString & |
label |
|
) |
| |
|
signal |
| void rtabmap::MainWindow::saveConfigGUI |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::saveFigures |
( |
| ) |
|
|
private |
| void rtabmap::MainWindow::selectFreenect |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectFreenect2 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectK4A |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectK4W2 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectMyntEyeS |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectOpenni |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectOpenni2 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectOpenniCv |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectOpenniCvAsus |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectRealSense |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectRealSense2 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectRealSense2Stereo |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectScreenCaptureFormat |
( |
bool |
checked | ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStereoDC1394 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStereoFlyCapture2 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStereoTara |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStereoUsb |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStereoZed |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::selectStream |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::sendGoal |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::sendWaypoints |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio |
( |
int |
w, |
|
|
int |
h |
|
) |
| |
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio1080p |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio16_10 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio16_9 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio240p |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio360p |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio480p |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio4_3 |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatio720p |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setAspectRatioCustom |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::setDefaultViews |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::setMonitoringState |
( |
bool |
pauseChecked = false | ) |
|
| void rtabmap::MainWindow::setNewDatabasePathOutput |
( |
const QString & |
newDatabasePathOutput | ) |
|
|
inlineprotected |
| void rtabmap::MainWindow::setupMainLayout |
( |
bool |
vertical | ) |
|
|
private |
| void rtabmap::MainWindow::showEvent |
( |
QShowEvent * |
anEvent | ) |
|
|
protectedvirtual |
| void rtabmap::MainWindow::startDetection |
( |
| ) |
|
|
protectedvirtualslot |
| const State& rtabmap::MainWindow::state |
( |
| ) |
const |
|
inlineprotected |
| void rtabmap::MainWindow::statsProcessed |
( |
| ) |
|
|
signal |
| void rtabmap::MainWindow::stopDetection |
( |
| ) |
|
|
protectedvirtualslot |
| void rtabmap::MainWindow::takeScreenshot |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::thresholdsChanged |
( |
int |
, |
|
|
int |
|
|
) |
| |
|
signal |
| void rtabmap::MainWindow::timeLimitChanged |
( |
float |
| ) |
|
|
signal |
| void rtabmap::MainWindow::triggerNewMap |
( |
| ) |
|
|
protectedvirtualslot |
| 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 |
( |
| ) |
|
|
inlineprotected |
| void rtabmap::MainWindow::update3DMapVisibility |
( |
bool |
cloudsShown, |
|
|
bool |
scansShown |
|
) |
| |
|
private |
| void rtabmap::MainWindow::updateCacheFromDatabase |
( |
const QString & |
path | ) |
|
|
slot |
| void rtabmap::MainWindow::updateCacheFromDatabase |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::updateEditMenu |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::updateElapsedTime |
( |
| ) |
|
|
protectedslot |
| void rtabmap::MainWindow::updateGraphView |
( |
| ) |
|
|
protectedslot |
| 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 |
| void rtabmap::MainWindow::updateNodeVisibility |
( |
int |
nodeId, |
|
|
bool |
visible |
|
) |
| |
|
protectedslot |
| void rtabmap::MainWindow::updateSelectSourceMenu |
( |
| ) |
|
|
private |
| void rtabmap::MainWindow::viewClouds |
( |
| ) |
|
|
protectedslot |
| QMap<QString, QByteArray> rtabmap::MainWindow::_autoScreenCaptureCachedImages |
|
private |
| bool rtabmap::MainWindow::_autoScreenCaptureOdomSync |
|
private |
| bool rtabmap::MainWindow::_autoScreenCapturePNG |
|
private |
| bool rtabmap::MainWindow::_autoScreenCaptureRAM |
|
private |
| std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > rtabmap::MainWindow::_cachedClouds |
|
private |
| std::set<int> rtabmap::MainWindow::_cachedEmptyClouds |
|
private |
| std::map<int, float> rtabmap::MainWindow::_cachedLocalizationsCount |
|
private |
| long rtabmap::MainWindow::_cachedMemoryUsage |
|
private |
| QMap<int, Signature> rtabmap::MainWindow::_cachedSignatures |
|
private |
| std::map<int, float> rtabmap::MainWindow::_cachedWordsCount |
|
private |
| long rtabmap::MainWindow::_createdCloudsMemoryUsage |
|
private |
| std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> rtabmap::MainWindow::_createdFeatures |
|
private |
| std::map<int, LaserScan> rtabmap::MainWindow::_createdScans |
|
private |
| std::map<int, Transform> rtabmap::MainWindow::_currentGTPosesMap |
|
private |
| std::map<int, std::string> rtabmap::MainWindow::_currentLabels |
|
private |
| std::multimap<int, Link> rtabmap::MainWindow::_currentLinksMap |
|
private |
| std::map<int, int> rtabmap::MainWindow::_currentMapIds |
|
private |
| std::map<int, Transform> rtabmap::MainWindow::_currentPosesMap |
|
private |
| bool rtabmap::MainWindow::_databaseUpdated |
|
private |
| QString rtabmap::MainWindow::_defaultOpenDatabasePath |
|
private |
| QTime* rtabmap::MainWindow::_elapsedTime |
|
private |
| QMap<int, QString> rtabmap::MainWindow::_exportPosesFileName |
|
private |
| int rtabmap::MainWindow::_exportPosesFrame |
|
private |
| bool rtabmap::MainWindow::_firstCall |
|
private |
| double rtabmap::MainWindow::_firstStamp |
|
private |
| QString rtabmap::MainWindow::_graphSavingFileName |
|
private |
| int rtabmap::MainWindow::_lastId |
|
private |
| QSet<int> rtabmap::MainWindow::_lastIds |
|
private |
| QTime* rtabmap::MainWindow::_logEventTime |
|
private |
| QVector<int> rtabmap::MainWindow::_loopClosureIds |
|
private |
| QString rtabmap::MainWindow::_newDatabasePath |
|
private |
| QString rtabmap::MainWindow::_newDatabasePathOutput |
|
private |
| Transform rtabmap::MainWindow::_odometryCorrection |
|
private |
| bool rtabmap::MainWindow::_odometryReceived |
|
private |
| bool rtabmap::MainWindow::_odomImageDepthShow |
|
private |
| bool rtabmap::MainWindow::_odomImageShow |
|
private |
| QTimer* rtabmap::MainWindow::_oneSecondTimer |
|
private |
| QString rtabmap::MainWindow::_openedDatabasePath |
|
private |
| std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> > rtabmap::MainWindow::_previousCloud |
|
private |
| bool rtabmap::MainWindow::_processingDownloadedMap |
|
private |
| bool rtabmap::MainWindow::_processingOdometry |
|
private |
| bool rtabmap::MainWindow::_processingStatistics |
|
private |
| bool rtabmap::MainWindow::_progressCanceled |
|
private |
| bool rtabmap::MainWindow::_recovering |
|
private |
| std::vector<CameraModel> rtabmap::MainWindow::_rectCameraModels |
|
private |
| QVector<int> rtabmap::MainWindow::_refIds |
|
private |
| bool rtabmap::MainWindow::_savedMaximized |
|
private |
| State rtabmap::MainWindow::_state |
|
private |
| Ui_mainWindow* rtabmap::MainWindow::_ui |
|
private |
| QStringList rtabmap::MainWindow::_waypoints |
|
private |
| int rtabmap::MainWindow::_waypointsIndex |
|
private |
The documentation for this class was generated from the following files: