#include <MainWindow.h>
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 ¶meters) |
Signals | |
void | cameraInfoProcessed () |
void | cameraInfoReceived (const rtabmap::SensorCaptureInfo &) |
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) |
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 () |
Public Member Functions inherited from UEventsHandler | |
void | registerToEventsManager () |
void | unregisterFromEventsManager () |
Public Member Functions inherited from UEventsSender | |
UEventsSender () | |
virtual | ~UEventsSender () |
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::CloudViewer * | cloudViewer () 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 |
std::map< int, Transform > | currentVisiblePosesMap () 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 |
void | postProcessing (bool refineNeighborLinks, bool refineLoopClosureLinks, bool detectMoreLoopClosures, double clusterRadius, double clusterAngle, int iterations, bool interSession, bool intraSession, bool sba, int sbaIterations, double sbaVariance, Optimizer::Type sbaType, double sbaRematchFeatures, bool abortIfDataMissing=true) |
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 () |
Protected Member Functions inherited from UEventsSender | |
void | post (UEvent *event, bool async=true) const |
Private Member Functions | |
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, const std::map< int, Transform > &odomCachePoses=std::map< int, Transform >(), const std::multimap< int, Link > &odomCacheConstraints=std::multimap< int, Link >(), bool verboseProgress=false, std::map< std::string, float > *stats=0) |
void | updateSelectSourceMenu () |
Definition at line 82 of file MainWindow.h.
Enumerator | |
---|---|
kIdle | |
kInitializing | |
kInitialized | |
kApplicationClosing | |
kClosing | |
kStartingDetection | |
kDetecting | |
kPaused | |
kMonitoring | |
kMonitoringPaused |
Definition at line 87 of file MainWindow.h.
rtabmap::MainWindow::MainWindow | ( | PreferencesDialog * | prefDialog = 0 , |
QWidget * | parent = 0 , |
||
bool | showSplashScreen = true |
||
) |
prefDialog | If NULL, a default dialog is created. This dialog is automatically destroyed with the MainWindow. |
Definition at line 142 of file MainWindow.cpp.
|
virtual |
Definition at line 723 of file MainWindow.cpp.
|
private |
Definition at line 4411 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7492 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4931 of file MainWindow.cpp.
|
private |
Definition at line 4936 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4866 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5371 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 303 of file MainWindow.h.
Definition at line 296 of file MainWindow.h.
|
signal |
|
signal |
|
protectedslot |
Definition at line 7323 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5376 of file MainWindow.cpp.
Definition at line 5330 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5315 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5310 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5325 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 8400 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5320 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7502 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5636 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 781 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 311 of file MainWindow.h.
|
protectedslot |
Definition at line 5382 of file MainWindow.cpp.
|
private |
Definition at line 3607 of file MainWindow.cpp.
|
private |
Definition at line 4293 of file MainWindow.cpp.
|
private |
Definition at line 3982 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 305 of file MainWindow.h.
Definition at line 304 of file MainWindow.h.
Definition at line 298 of file MainWindow.h.
|
inlineprotected |
Definition at line 302 of file MainWindow.h.
Definition at line 300 of file MainWindow.h.
Definition at line 301 of file MainWindow.h.
Definition at line 297 of file MainWindow.h.
Definition at line 752 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8338 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8383 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7057 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7041 of file MainWindow.cpp.
|
signal |
|
protectedvirtualslot |
Definition at line 7403 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7447 of file MainWindow.cpp.
|
private |
Definition at line 4982 of file MainWindow.cpp.
Definition at line 5143 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7251 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7256 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5682 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5253 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8258 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7941 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7871 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8054 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8016 of file MainWindow.cpp.
|
private |
Definition at line 6257 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6252 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6244 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6228 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6236 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6240 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6232 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6248 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6196 of file MainWindow.cpp.
|
inlineprotectedvirtual |
Definition at line 320 of file MainWindow.h.
QString rtabmap::MainWindow::getWorkingDirectory | ( | ) | const |
Definition at line 7090 of file MainWindow.cpp.
|
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.
Implements UEventsHandler.
Definition at line 876 of file MainWindow.cpp.
|
signal |
|
inline |
Definition at line 115 of file MainWindow.h.
|
inline |
Definition at line 113 of file MainWindow.h.
|
inline |
Definition at line 112 of file MainWindow.h.
|
inline |
Definition at line 110 of file MainWindow.h.
|
protectedvirtual |
Definition at line 5244 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7331 of file MainWindow.cpp.
|
private |
Definition at line 7612 of file MainWindow.cpp.
|
signal |
|
inlineprotected |
Definition at line 312 of file MainWindow.h.
|
signal |
|
protectedvirtual |
Definition at line 5223 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5431 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 318 of file MainWindow.h.
|
signal |
|
protectedslot |
Definition at line 6170 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 307 of file MainWindow.h.
|
inlineprotected |
Definition at line 308 of file MainWindow.h.
|
signal |
|
signal |
|
protectedvirtualslot |
Definition at line 5521 of file MainWindow.cpp.
|
slot |
Definition at line 5530 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7570 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7667 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7673 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7095 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 6074 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7296 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7304 of file MainWindow.cpp.
|
protected |
Definition at line 6483 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6177 of file MainWindow.cpp.
|
protectedslot |
Definition at line 1017 of file MainWindow.cpp.
|
protectedslot |
Definition at line 1041 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4666 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4540 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4783 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4857 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4842 of file MainWindow.cpp.
|
virtualslot |
Definition at line 1943 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 310 of file MainWindow.h.
|
protectedslot |
Definition at line 7342 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 8326 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5236 of file MainWindow.cpp.
|
signal |
|
signal |
|
signal |
|
signal |
|
signal |
|
signal |
|
protectedvirtualslot |
Definition at line 5410 of file MainWindow.cpp.
|
private |
Definition at line 7591 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7226 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7231 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7236 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7139 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7159 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7169 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7164 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7221 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7134 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7154 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7144 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7149 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7174 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7179 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7183 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7188 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7703 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7193 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7198 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7211 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7216 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7202 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7206 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7246 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7241 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7261 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7275 of file MainWindow.cpp.
Definition at line 7791 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7852 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7822 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7817 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7832 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7837 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7842 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7827 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7847 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7857 of file MainWindow.cpp.
|
protected |
Definition at line 757 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7680 of file MainWindow.cpp.
|
protected |
Definition at line 771 of file MainWindow.cpp.
void rtabmap::MainWindow::setMonitoringState | ( | bool | pauseChecked = false | ) |
Definition at line 8394 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 317 of file MainWindow.h.
|
private |
Definition at line 740 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5217 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6460 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5725 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 294 of file MainWindow.h.
|
signal |
|
signal |
|
signal |
|
protectedvirtualslot |
Definition at line 6108 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7786 of file MainWindow.cpp.
|
signal |
|
protectedvirtualslot |
Definition at line 8332 of file MainWindow.cpp.
|
signal |
|
inlineprotected |
Definition at line 293 of file MainWindow.h.
|
private |
|
protectedslot |
Definition at line 7353 of file MainWindow.cpp.
|
slot |
Definition at line 7363 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7118 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7582 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4523 of file MainWindow.cpp.
|
private |
Definition at line 2750 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4465 of file MainWindow.cpp.
|
slot |
Definition at line 5387 of file MainWindow.cpp.
|
private |
Definition at line 5266 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7978 of file MainWindow.cpp.
|
private |
Definition at line 350 of file MainWindow.h.
|
private |
Definition at line 425 of file MainWindow.h.
|
private |
Definition at line 422 of file MainWindow.h.
|
private |
Definition at line 424 of file MainWindow.h.
|
private |
Definition at line 423 of file MainWindow.h.
|
private |
Definition at line 384 of file MainWindow.h.
Definition at line 386 of file MainWindow.h.
Definition at line 389 of file MainWindow.h.
|
private |
Definition at line 390 of file MainWindow.h.
|
private |
Definition at line 378 of file MainWindow.h.
Definition at line 377 of file MainWindow.h.
Definition at line 388 of file MainWindow.h.
|
private |
Definition at line 416 of file MainWindow.h.
|
private |
Definition at line 385 of file MainWindow.h.
|
private |
Definition at line 398 of file MainWindow.h.
Definition at line 392 of file MainWindow.h.
Definition at line 380 of file MainWindow.h.
|
private |
Definition at line 383 of file MainWindow.h.
Definition at line 381 of file MainWindow.h.
Definition at line 382 of file MainWindow.h.
Definition at line 379 of file MainWindow.h.
|
private |
Definition at line 368 of file MainWindow.h.
|
private |
Definition at line 355 of file MainWindow.h.
|
private |
Definition at line 367 of file MainWindow.h.
|
private |
Definition at line 354 of file MainWindow.h.
|
private |
Definition at line 405 of file MainWindow.h.
|
private |
Definition at line 396 of file MainWindow.h.
|
private |
Definition at line 352 of file MainWindow.h.
|
private |
Definition at line 351 of file MainWindow.h.
|
private |
Definition at line 421 of file MainWindow.h.
|
private |
Definition at line 420 of file MainWindow.h.
|
private |
Definition at line 430 of file MainWindow.h.
|
private |
Definition at line 359 of file MainWindow.h.
|
private |
Definition at line 419 of file MainWindow.h.
|
private |
Definition at line 346 of file MainWindow.h.
|
private |
Definition at line 358 of file MainWindow.h.
|
private |
Definition at line 357 of file MainWindow.h.
|
private |
Definition at line 401 of file MainWindow.h.
|
private |
Definition at line 409 of file MainWindow.h.
|
private |
Definition at line 406 of file MainWindow.h.
|
private |
Definition at line 428 of file MainWindow.h.
|
private |
Definition at line 417 of file MainWindow.h.
|
private |
Definition at line 412 of file MainWindow.h.
|
private |
Definition at line 364 of file MainWindow.h.
|
private |
Definition at line 365 of file MainWindow.h.
|
private |
Definition at line 394 of file MainWindow.h.
|
private |
Definition at line 395 of file MainWindow.h.
|
private |
Definition at line 400 of file MainWindow.h.
|
private |
Definition at line 363 of file MainWindow.h.
|
private |
Definition at line 370 of file MainWindow.h.
|
private |
Definition at line 369 of file MainWindow.h.
|
private |
Definition at line 345 of file MainWindow.h.
|
private |
Definition at line 404 of file MainWindow.h.
|
private |
Definition at line 366 of file MainWindow.h.
|
private |
Definition at line 408 of file MainWindow.h.
|
private |
Definition at line 353 of file MainWindow.h.
|
private |
Definition at line 349 of file MainWindow.h.
|
private |
Definition at line 387 of file MainWindow.h.
|
private |
Definition at line 361 of file MainWindow.h.
|
private |
Definition at line 402 of file MainWindow.h.
|
private |
Definition at line 360 of file MainWindow.h.
|
private |
Definition at line 431 of file MainWindow.h.
|
private |
Definition at line 414 of file MainWindow.h.
|
private |
Definition at line 410 of file MainWindow.h.
|
private |
Definition at line 362 of file MainWindow.h.
|
private |
Definition at line 374 of file MainWindow.h.
|
private |
Definition at line 375 of file MainWindow.h.
|
private |
Definition at line 427 of file MainWindow.h.
|
private |
Definition at line 371 of file MainWindow.h.
|
private |
Definition at line 344 of file MainWindow.h.
|
private |
Definition at line 343 of file MainWindow.h.
|
private |
Definition at line 341 of file MainWindow.h.
|
private |
Definition at line 372 of file MainWindow.h.
|
private |
Definition at line 373 of file MainWindow.h.