#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 () |
![]() | |
void | registerToEventsManager () |
void | unregisterFromEventsManager () |
![]() | |
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 () |
![]() | |
UEventsHandler () | |
virtual | ~UEventsHandler () |
![]() | |
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 725 of file MainWindow.cpp.
|
private |
Definition at line 4436 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7517 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4956 of file MainWindow.cpp.
|
private |
Definition at line 4961 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4891 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5396 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 7348 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5401 of file MainWindow.cpp.
Definition at line 5355 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5340 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5335 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5350 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 8440 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5345 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7527 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5661 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 783 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 311 of file MainWindow.h.
|
protectedslot |
Definition at line 5407 of file MainWindow.cpp.
|
private |
Definition at line 3632 of file MainWindow.cpp.
|
private |
Definition at line 4318 of file MainWindow.cpp.
|
private |
Definition at line 4007 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 754 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8378 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8423 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7082 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7066 of file MainWindow.cpp.
|
signal |
|
protectedvirtualslot |
Definition at line 7428 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7472 of file MainWindow.cpp.
|
private |
Definition at line 5007 of file MainWindow.cpp.
Definition at line 5168 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7276 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7281 of file MainWindow.cpp.
|
protectedslot |
Definition at line 5707 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5278 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8283 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7966 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7896 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8079 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8041 of file MainWindow.cpp.
|
private |
Definition at line 6282 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6277 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6269 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6253 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6261 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6265 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6257 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6273 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6221 of file MainWindow.cpp.
|
inlineprotectedvirtual |
Definition at line 320 of file MainWindow.h.
QString rtabmap::MainWindow::getWorkingDirectory | ( | ) | const |
Definition at line 7115 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 878 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 5269 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7356 of file MainWindow.cpp.
|
private |
Definition at line 7637 of file MainWindow.cpp.
|
signal |
|
inlineprotected |
Definition at line 312 of file MainWindow.h.
|
signal |
|
protectedvirtual |
Definition at line 5248 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5456 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 318 of file MainWindow.h.
|
signal |
|
protectedslot |
Definition at line 6195 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 5546 of file MainWindow.cpp.
|
slot |
Definition at line 5555 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7595 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7692 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7698 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7120 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 6099 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7321 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7329 of file MainWindow.cpp.
|
protected |
Definition at line 6508 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6202 of file MainWindow.cpp.
|
protectedslot |
Definition at line 1019 of file MainWindow.cpp.
|
protectedslot |
Definition at line 1043 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4691 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4565 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4808 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4882 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4867 of file MainWindow.cpp.
|
virtualslot |
Definition at line 1968 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 310 of file MainWindow.h.
|
protectedslot |
Definition at line 7367 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 8366 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5261 of file MainWindow.cpp.
|
signal |
|
signal |
|
signal |
|
signal |
|
signal |
|
signal |
|
protectedvirtualslot |
Definition at line 5435 of file MainWindow.cpp.
|
private |
Definition at line 7616 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 7261 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7164 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7184 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7194 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7189 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7246 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7159 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7179 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7169 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7174 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7199 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7204 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7208 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7213 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7728 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7218 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7223 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7236 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7241 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7227 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7231 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7271 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7266 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7286 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7300 of file MainWindow.cpp.
Definition at line 7816 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7877 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7847 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7842 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7857 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7862 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7867 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7852 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7872 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7882 of file MainWindow.cpp.
|
protected |
Definition at line 759 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 7705 of file MainWindow.cpp.
|
protected |
Definition at line 773 of file MainWindow.cpp.
void rtabmap::MainWindow::setMonitoringState | ( | bool | pauseChecked = false | ) |
Definition at line 8434 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 317 of file MainWindow.h.
|
private |
Definition at line 742 of file MainWindow.cpp.
|
protectedvirtual |
Definition at line 5242 of file MainWindow.cpp.
|
protectedslot |
Definition at line 6485 of file MainWindow.cpp.
|
protectedvirtualslot |
Definition at line 5750 of file MainWindow.cpp.
|
inlineprotected |
Definition at line 294 of file MainWindow.h.
|
signal |
|
signal |
|
signal |
|
protectedvirtualslot |
Definition at line 6133 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7811 of file MainWindow.cpp.
|
signal |
|
protectedvirtualslot |
Definition at line 8372 of file MainWindow.cpp.
|
signal |
|
inlineprotected |
Definition at line 293 of file MainWindow.h.
|
private |
|
protectedslot |
Definition at line 7378 of file MainWindow.cpp.
|
slot |
Definition at line 7388 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7143 of file MainWindow.cpp.
|
protectedslot |
Definition at line 7607 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4548 of file MainWindow.cpp.
|
private |
Definition at line 2775 of file MainWindow.cpp.
|
protectedslot |
Definition at line 4490 of file MainWindow.cpp.
|
slot |
Definition at line 5412 of file MainWindow.cpp.
|
private |
Definition at line 5291 of file MainWindow.cpp.
|
protectedslot |
Definition at line 8003 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.