#include <MainWindow.h>
Definition at line 74 of file MainWindow.h.
kIdle | |
kInitializing | |
kInitialized | |
kApplicationClosing | |
kClosing | |
kStartingDetection | |
kDetecting | |
kPaused | |
kMonitoring | |
kMonitoringPaused |
Definition at line 79 of file MainWindow.h.
rtabmap::MainWindow::MainWindow | ( | PreferencesDialog * | prefDialog = 0 , |
QWidget * | parent = 0 |
||
) |
prefDialog | If NULL, a default dialog is created. This dialog is automatically destroyed with the MainWindow. |
Definition at line 128 of file MainWindow.cpp.
rtabmap::MainWindow::~MainWindow | ( | ) | [virtual] |
Definition at line 584 of file MainWindow.cpp.
Transform rtabmap::MainWindow::alignPosesToGroundTruth | ( | std::map< int, Transform > & | poses, |
const std::map< int, Transform > & | groundTruth | ||
) | [private] |
Definition at line 2864 of file MainWindow.cpp.
void rtabmap::MainWindow::anchorCloudsToGroundTruth | ( | ) | [private, slot] |
Definition at line 4995 of file MainWindow.cpp.
void rtabmap::MainWindow::applyPrefSettings | ( | PreferencesDialog::PANEL_FLAGS | flags | ) | [private, slot] |
Definition at line 3272 of file MainWindow.cpp.
void rtabmap::MainWindow::applyPrefSettings | ( | const rtabmap::ParametersMap & | parameters | ) | [private, slot] |
Definition at line 3332 of file MainWindow.cpp.
void rtabmap::MainWindow::applyPrefSettings | ( | const rtabmap::ParametersMap & | parameters, |
bool | postParamEvent | ||
) | [private] |
Definition at line 3337 of file MainWindow.cpp.
void rtabmap::MainWindow::beep | ( | ) | [private, slot] |
Definition at line 3655 of file MainWindow.cpp.
void rtabmap::MainWindow::cameraInfoReceived | ( | const rtabmap::CameraInfo & | ) | [signal] |
void rtabmap::MainWindow::cancelGoal | ( | ) | [private, slot] |
Definition at line 4842 of file MainWindow.cpp.
QString rtabmap::MainWindow::captureScreen | ( | bool | cacheInRAM = false | ) | [private] |
Definition at line 3614 of file MainWindow.cpp.
void rtabmap::MainWindow::changeDetectionRateSetting | ( | ) | [private, slot] |
Definition at line 3599 of file MainWindow.cpp.
void rtabmap::MainWindow::changeImgRateSetting | ( | ) | [private, slot] |
Definition at line 3594 of file MainWindow.cpp.
void rtabmap::MainWindow::changeMappingMode | ( | ) | [private, slot] |
Definition at line 3609 of file MainWindow.cpp.
void rtabmap::MainWindow::changeState | ( | MainWindow::State | state | ) | [private, slot] |
Definition at line 5839 of file MainWindow.cpp.
void rtabmap::MainWindow::changeTimeLimitSetting | ( | ) | [private, slot] |
Definition at line 3604 of file MainWindow.cpp.
void rtabmap::MainWindow::clearTheCache | ( | ) | [private, slot] |
Definition at line 5005 of file MainWindow.cpp.
bool rtabmap::MainWindow::closeDatabase | ( | ) | [private, slot] |
Definition at line 3815 of file MainWindow.cpp.
void rtabmap::MainWindow::closeEvent | ( | QCloseEvent * | event | ) | [protected, virtual] |
Definition at line 605 of file MainWindow.cpp.
void rtabmap::MainWindow::configGUIModified | ( | ) | [private, slot] |
Definition at line 3660 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 2312 of file MainWindow.cpp.
void rtabmap::MainWindow::createAndAddFeaturesToMap | ( | int | nodeId, |
const Transform & | pose, | ||
int | mapId | ||
) | [private] |
Definition at line 2772 of file MainWindow.cpp.
void rtabmap::MainWindow::createAndAddProjectionMap | ( | const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, |
const pcl::IndicesPtr & | indices, | ||
int | nodeId, | ||
const Transform & | pose, | ||
bool | updateOctomap = false |
||
) | [private] |
Definition at line 2576 of file MainWindow.cpp.
void rtabmap::MainWindow::createAndAddScanToMap | ( | int | nodeId, |
const Transform & | pose, | ||
int | mapId | ||
) | [private] |
Definition at line 2673 of file MainWindow.cpp.
void rtabmap::MainWindow::dataRecorder | ( | ) | [private, slot] |
Definition at line 5777 of file MainWindow.cpp.
void rtabmap::MainWindow::dataRecorderDestroyed | ( | ) | [private, slot] |
Definition at line 5822 of file MainWindow.cpp.
void rtabmap::MainWindow::deleteMemory | ( | ) | [private, slot] |
Definition at line 4647 of file MainWindow.cpp.
void rtabmap::MainWindow::detectionRateChanged | ( | double | ) | [signal] |
void rtabmap::MainWindow::downloadAllClouds | ( | ) | [private, slot] |
Definition at line 4906 of file MainWindow.cpp.
void rtabmap::MainWindow::downloadPoseGraph | ( | ) | [private, slot] |
Definition at line 4950 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 3394 of file MainWindow.cpp.
void rtabmap::MainWindow::dumpTheMemory | ( | ) | [private, slot] |
Definition at line 4778 of file MainWindow.cpp.
void rtabmap::MainWindow::dumpThePrediction | ( | ) | [private, slot] |
Definition at line 4783 of file MainWindow.cpp.
void rtabmap::MainWindow::editDatabase | ( | ) | [private, slot] |
Definition at line 3861 of file MainWindow.cpp.
bool rtabmap::MainWindow::eventFilter | ( | QObject * | obj, |
QEvent * | event | ||
) | [protected, virtual] |
Definition at line 3553 of file MainWindow.cpp.
void rtabmap::MainWindow::exportBundlerFormat | ( | ) | [private, slot] |
Definition at line 5653 of file MainWindow.cpp.
void rtabmap::MainWindow::exportClouds | ( | ) | [private, slot] |
Definition at line 5415 of file MainWindow.cpp.
void rtabmap::MainWindow::exportGridMap | ( | ) | [private, slot] |
Definition at line 5317 of file MainWindow.cpp.
void rtabmap::MainWindow::exportImages | ( | ) | [private, slot] |
Definition at line 5486 of file MainWindow.cpp.
void rtabmap::MainWindow::exportOctomap | ( | ) | [private, slot] |
Definition at line 5448 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPoses | ( | int | format | ) | [private] |
Definition at line 4224 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPosesG2O | ( | ) | [private, slot] |
Definition at line 4219 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPosesKITTI | ( | ) | [private, slot] |
Definition at line 4211 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPosesRaw | ( | ) | [private, slot] |
Definition at line 4203 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPosesRGBDSLAM | ( | ) | [private, slot] |
Definition at line 4207 of file MainWindow.cpp.
void rtabmap::MainWindow::exportPosesTORO | ( | ) | [private, slot] |
Definition at line 4215 of file MainWindow.cpp.
void rtabmap::MainWindow::exportScans | ( | ) | [private, slot] |
Definition at line 5384 of file MainWindow.cpp.
void rtabmap::MainWindow::generateGraphDOT | ( | ) | [private, slot] |
Definition at line 4171 of file MainWindow.cpp.
QString rtabmap::MainWindow::getWorkingDirectory | ( | ) | const |
Definition at line 4680 of file MainWindow.cpp.
void 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 but must not be deleted.
Implements UEventsHandler.
Definition at line 694 of file MainWindow.cpp.
void rtabmap::MainWindow::imgRateChanged | ( | double | ) | [signal] |
bool rtabmap::MainWindow::isProcessingOdometry | ( | ) | const [inline] |
Definition at line 105 of file MainWindow.h.
bool rtabmap::MainWindow::isProcessingStatistics | ( | ) | const [inline] |
Definition at line 104 of file MainWindow.h.
bool rtabmap::MainWindow::isSavedMaximized | ( | ) | const [inline] |
Definition at line 102 of file MainWindow.h.
void rtabmap::MainWindow::label | ( | ) | [private, slot] |
Definition at line 4850 of file MainWindow.cpp.
void rtabmap::MainWindow::loadFigures | ( | ) | [private] |
Definition at line 5096 of file MainWindow.cpp.
void rtabmap::MainWindow::loopClosureThrChanged | ( | float | ) | [signal] |
void rtabmap::MainWindow::mappingModeChanged | ( | bool | ) | [signal] |
void rtabmap::MainWindow::moveEvent | ( | QMoveEvent * | anEvent | ) | [protected, virtual] |
Definition at line 3532 of file MainWindow.cpp.
void rtabmap::MainWindow::newDatabase | ( | ) | [private, slot] |
Definition at line 3685 of file MainWindow.cpp.
void rtabmap::MainWindow::noMoreImagesReceived | ( | ) | [signal] |
void rtabmap::MainWindow::notifyNoMoreImages | ( | ) | [private, slot] |
Definition at line 4145 of file MainWindow.cpp.
void rtabmap::MainWindow::odometryReceived | ( | const rtabmap::OdometryEvent & | , |
bool | |||
) | [signal] |
void rtabmap::MainWindow::openDatabase | ( | const QString & | path | ) | [slot] |
Definition at line 3740 of file MainWindow.cpp.
void rtabmap::MainWindow::openDatabase | ( | ) | [private, slot] |
Definition at line 3731 of file MainWindow.cpp.
void rtabmap::MainWindow::openPreferences | ( | ) | [private, slot] |
Definition at line 5129 of file MainWindow.cpp.
void rtabmap::MainWindow::openPreferencesSource | ( | ) | [private, slot] |
Definition at line 5135 of file MainWindow.cpp.
void rtabmap::MainWindow::openWorkingDirectory | ( | ) | [private, slot] |
Definition at line 4685 of file MainWindow.cpp.
void rtabmap::MainWindow::pauseDetection | ( | ) | [private, slot] |
Definition at line 4059 of file MainWindow.cpp.
void rtabmap::MainWindow::postGoal | ( | const QString & | goal | ) | [private, slot] |
Definition at line 4823 of file MainWindow.cpp.
void rtabmap::MainWindow::postProcessing | ( | ) | [private, slot] |
Definition at line 4283 of file MainWindow.cpp.
void rtabmap::MainWindow::printLoopClosureIds | ( | ) | [private, slot] |
Definition at line 4152 of file MainWindow.cpp.
void rtabmap::MainWindow::processCameraInfo | ( | const rtabmap::CameraInfo & | info | ) | [private, slot] |
Definition at line 830 of file MainWindow.cpp.
void rtabmap::MainWindow::processOdometry | ( | const rtabmap::OdometryEvent & | odom, |
bool | dataIgnored | ||
) | [private, slot] |
Definition at line 844 of file MainWindow.cpp.
void rtabmap::MainWindow::processRtabmapEvent3DMap | ( | const rtabmap::RtabmapEvent3DMap & | event | ) | [private, slot] |
Definition at line 3101 of file MainWindow.cpp.
void rtabmap::MainWindow::processRtabmapEventInit | ( | int | status, |
const QString & | info | ||
) | [private, slot] |
Definition at line 2975 of file MainWindow.cpp.
void rtabmap::MainWindow::processRtabmapGlobalPathEvent | ( | const rtabmap::RtabmapGlobalPathEvent & | event | ) | [private, slot] |
Definition at line 3190 of file MainWindow.cpp.
void rtabmap::MainWindow::processRtabmapGoalStatusEvent | ( | int | status | ) | [private, slot] |
Definition at line 3263 of file MainWindow.cpp.
void rtabmap::MainWindow::processRtabmapLabelErrorEvent | ( | int | id, |
const QString & | label | ||
) | [private, slot] |
Definition at line 3248 of file MainWindow.cpp.
void rtabmap::MainWindow::processStats | ( | const rtabmap::Statistics & | stat | ) | [slot] |
Definition at line 1315 of file MainWindow.cpp.
void rtabmap::MainWindow::resetOdometry | ( | ) | [private, slot] |
Definition at line 5765 of file MainWindow.cpp.
void rtabmap::MainWindow::resizeEvent | ( | QResizeEvent * | anEvent | ) | [protected, virtual] |
Definition at line 3545 of file MainWindow.cpp.
void rtabmap::MainWindow::rtabmapEvent3DMapReceived | ( | const rtabmap::RtabmapEvent3DMap & | event | ) | [signal] |
void rtabmap::MainWindow::rtabmapEventInitReceived | ( | int | status, |
const QString & | info | ||
) | [signal] |
void rtabmap::MainWindow::rtabmapGlobalPathEventReceived | ( | const rtabmap::RtabmapGlobalPathEvent & | event | ) | [signal] |
void rtabmap::MainWindow::rtabmapGoalStatusEventReceived | ( | int | status | ) | [signal] |
void rtabmap::MainWindow::rtabmapLabelErrorReceived | ( | int | id, |
const QString & | label | ||
) | [signal] |
void rtabmap::MainWindow::saveConfigGUI | ( | ) | [private, slot] |
Definition at line 3666 of file MainWindow.cpp.
void rtabmap::MainWindow::saveFigures | ( | ) | [private] |
Definition at line 5077 of file MainWindow.cpp.
void rtabmap::MainWindow::selectFreenect | ( | ) | [private, slot] |
Definition at line 4734 of file MainWindow.cpp.
void rtabmap::MainWindow::selectFreenect2 | ( | ) | [private, slot] |
Definition at line 4754 of file MainWindow.cpp.
void rtabmap::MainWindow::selectOpenni | ( | ) | [private, slot] |
Definition at line 4729 of file MainWindow.cpp.
void rtabmap::MainWindow::selectOpenni2 | ( | ) | [private, slot] |
Definition at line 4749 of file MainWindow.cpp.
void rtabmap::MainWindow::selectOpenniCv | ( | ) | [private, slot] |
Definition at line 4739 of file MainWindow.cpp.
void rtabmap::MainWindow::selectOpenniCvAsus | ( | ) | [private, slot] |
Definition at line 4744 of file MainWindow.cpp.
void rtabmap::MainWindow::selectScreenCaptureFormat | ( | bool | checked | ) | [private, slot] |
Definition at line 5162 of file MainWindow.cpp.
void rtabmap::MainWindow::selectStereoDC1394 | ( | ) | [private, slot] |
Definition at line 4759 of file MainWindow.cpp.
void rtabmap::MainWindow::selectStereoFlyCapture2 | ( | ) | [private, slot] |
Definition at line 4764 of file MainWindow.cpp.
void rtabmap::MainWindow::selectStereoUsb | ( | ) | [private, slot] |
Definition at line 4773 of file MainWindow.cpp.
void rtabmap::MainWindow::selectStereoZed | ( | ) | [private, slot] |
Definition at line 4768 of file MainWindow.cpp.
void rtabmap::MainWindow::selectStream | ( | ) | [private, slot] |
Definition at line 4724 of file MainWindow.cpp.
void rtabmap::MainWindow::sendGoal | ( | ) | [private, slot] |
Definition at line 4788 of file MainWindow.cpp.
void rtabmap::MainWindow::sendWaypoints | ( | ) | [private, slot] |
Definition at line 4802 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio | ( | int | w, |
int | h | ||
) | [private, slot] |
Definition at line 5237 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio1080p | ( | ) | [private, slot] |
Definition at line 5298 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio16_10 | ( | ) | [private, slot] |
Definition at line 5268 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio16_9 | ( | ) | [private, slot] |
Definition at line 5263 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio240p | ( | ) | [private, slot] |
Definition at line 5278 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio360p | ( | ) | [private, slot] |
Definition at line 5283 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio480p | ( | ) | [private, slot] |
Definition at line 5288 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio4_3 | ( | ) | [private, slot] |
Definition at line 5273 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatio720p | ( | ) | [private, slot] |
Definition at line 5293 of file MainWindow.cpp.
void rtabmap::MainWindow::setAspectRatioCustom | ( | ) | [private, slot] |
Definition at line 5303 of file MainWindow.cpp.
void rtabmap::MainWindow::setDefaultViews | ( | ) | [private, slot] |
Definition at line 5142 of file MainWindow.cpp.
void rtabmap::MainWindow::setMonitoringState | ( | bool | pauseChecked = false | ) |
Definition at line 5833 of file MainWindow.cpp.
void rtabmap::MainWindow::setupMainLayout | ( | bool | vertical | ) | [private] |
Definition at line 593 of file MainWindow.cpp.
void rtabmap::MainWindow::showEvent | ( | QShowEvent * | anEvent | ) | [protected, virtual] |
Definition at line 3526 of file MainWindow.cpp.
void rtabmap::MainWindow::startDetection | ( | ) | [private, slot] |
Definition at line 3889 of file MainWindow.cpp.
void rtabmap::MainWindow::stateChanged | ( | MainWindow::State | ) | [signal] |
void rtabmap::MainWindow::statsReceived | ( | const rtabmap::Statistics & | ) | [signal] |
void rtabmap::MainWindow::stopDetection | ( | ) | [private, slot] |
Definition at line 4093 of file MainWindow.cpp.
void rtabmap::MainWindow::takeScreenshot | ( | ) | [private, slot] |
Definition at line 5232 of file MainWindow.cpp.
void rtabmap::MainWindow::thresholdsChanged | ( | int | , |
int | |||
) | [signal] |
void rtabmap::MainWindow::timeLimitChanged | ( | float | ) | [signal] |
void rtabmap::MainWindow::triggerNewMap | ( | ) | [private, slot] |
Definition at line 5771 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] |
void rtabmap::MainWindow::update3DMapVisibility | ( | bool | cloudsShown, |
bool | scansShown | ||
) | [private] |
void rtabmap::MainWindow::updateCacheFromDatabase | ( | const QString & | path | ) | [slot] |
Definition at line 4871 of file MainWindow.cpp.
void rtabmap::MainWindow::updateCacheFromDatabase | ( | ) | [private, slot] |
Definition at line 4861 of file MainWindow.cpp.
void rtabmap::MainWindow::updateEditMenu | ( | ) | [private, slot] |
Definition at line 4708 of file MainWindow.cpp.
void rtabmap::MainWindow::updateElapsedTime | ( | ) | [private, slot] |
Definition at line 5068 of file MainWindow.cpp.
void rtabmap::MainWindow::updateGraphView | ( | ) | [private, slot] |
Definition at line 2958 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 |
||
) | [private] |
Definition at line 1840 of file MainWindow.cpp.
void rtabmap::MainWindow::updateNodeVisibility | ( | int | nodeId, |
bool | visible | ||
) | [private, slot] |
Definition at line 2914 of file MainWindow.cpp.
void rtabmap::MainWindow::updateSelectSourceMenu | ( | ) | [private] |
Definition at line 3566 of file MainWindow.cpp.
void rtabmap::MainWindow::viewClouds | ( | ) | [private, slot] |
Definition at line 5431 of file MainWindow.cpp.
void rtabmap::MainWindow::viewScans | ( | ) | [private, slot] |
Definition at line 5399 of file MainWindow.cpp.
AboutDialog* rtabmap::MainWindow::_aboutDialog [private] |
Definition at line 267 of file MainWindow.h.
QMap<QString, QByteArray> rtabmap::MainWindow::_autoScreenCaptureCachedImages [private] |
Definition at line 329 of file MainWindow.h.
bool rtabmap::MainWindow::_autoScreenCaptureOdomSync [private] |
Definition at line 327 of file MainWindow.h.
bool rtabmap::MainWindow::_autoScreenCaptureRAM [private] |
Definition at line 328 of file MainWindow.h.
std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > rtabmap::MainWindow::_cachedClouds [private] |
Definition at line 296 of file MainWindow.h.
long rtabmap::MainWindow::_cachedMemoryUsage [private] |
Definition at line 290 of file MainWindow.h.
QMap<int, Signature> rtabmap::MainWindow::_cachedSignatures [private] |
Definition at line 289 of file MainWindow.h.
Definition at line 262 of file MainWindow.h.
CloudViewer* rtabmap::MainWindow::_cloudViewer [private] |
Definition at line 322 of file MainWindow.h.
long rtabmap::MainWindow::_createdCloudsMemoryUsage [private] |
Definition at line 297 of file MainWindow.h.
std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> rtabmap::MainWindow::_createdFeatures [private] |
Definition at line 306 of file MainWindow.h.
std::map<int, cv::Mat> rtabmap::MainWindow::_createdScans [private] |
Definition at line 300 of file MainWindow.h.
std::map<int, Transform> rtabmap::MainWindow::_currentGTPosesMap [private] |
Definition at line 292 of file MainWindow.h.
std::map<int, std::string> rtabmap::MainWindow::_currentLabels [private] |
Definition at line 295 of file MainWindow.h.
std::multimap<int, Link> rtabmap::MainWindow::_currentLinksMap [private] |
Definition at line 293 of file MainWindow.h.
std::map<int, int> rtabmap::MainWindow::_currentMapIds [private] |
Definition at line 294 of file MainWindow.h.
std::map<int, Transform> rtabmap::MainWindow::_currentPosesMap [private] |
Definition at line 291 of file MainWindow.h.
bool rtabmap::MainWindow::_databaseUpdated [private] |
Definition at line 282 of file MainWindow.h.
DataRecorder* rtabmap::MainWindow::_dataRecorder [private] |
Definition at line 271 of file MainWindow.h.
QTime* rtabmap::MainWindow::_elapsedTime [private] |
Definition at line 313 of file MainWindow.h.
Definition at line 268 of file MainWindow.h.
QMap<int, QString> rtabmap::MainWindow::_exportPosesFileName [private] |
Definition at line 326 of file MainWindow.h.
Definition at line 269 of file MainWindow.h.
bool rtabmap::MainWindow::_firstCall [private] |
Definition at line 334 of file MainWindow.h.
double rtabmap::MainWindow::_firstStamp [private] |
Definition at line 275 of file MainWindow.h.
QString rtabmap::MainWindow::_graphSavingFileName [private] |
Definition at line 325 of file MainWindow.h.
std::map<int, std::pair<cv::Mat, cv::Mat> > rtabmap::MainWindow::_gridLocalMaps [private] |
Definition at line 302 of file MainWindow.h.
Definition at line 320 of file MainWindow.h.
int rtabmap::MainWindow::_lastId [private] |
Definition at line 274 of file MainWindow.h.
QSet<int> rtabmap::MainWindow::_lastIds [private] |
Definition at line 273 of file MainWindow.h.
Transform rtabmap::MainWindow::_lastOdomPose [private] |
Definition at line 309 of file MainWindow.h.
Definition at line 317 of file MainWindow.h.
QTime* rtabmap::MainWindow::_logEventTime [private] |
Definition at line 314 of file MainWindow.h.
QVector<int> rtabmap::MainWindow::_loopClosureIds [private] |
Definition at line 332 of file MainWindow.h.
Definition at line 323 of file MainWindow.h.
QString rtabmap::MainWindow::_newDatabasePath [private] |
Definition at line 279 of file MainWindow.h.
QString rtabmap::MainWindow::_newDatabasePathOutput [private] |
Definition at line 280 of file MainWindow.h.
rtabmap::OctoMap* rtabmap::MainWindow::_octomap [private] |
Definition at line 304 of file MainWindow.h.
Definition at line 308 of file MainWindow.h.
bool rtabmap::MainWindow::_odometryReceived [private] |
Definition at line 278 of file MainWindow.h.
bool rtabmap::MainWindow::_odomImageDepthShow [private] |
Definition at line 284 of file MainWindow.h.
bool rtabmap::MainWindow::_odomImageShow [private] |
Definition at line 283 of file MainWindow.h.
Definition at line 263 of file MainWindow.h.
QTimer* rtabmap::MainWindow::_oneSecondTimer [private] |
Definition at line 312 of file MainWindow.h.
QString rtabmap::MainWindow::_openedDatabasePath [private] |
Definition at line 281 of file MainWindow.h.
PdfPlotCurve* rtabmap::MainWindow::_posteriorCurve [private] |
Definition at line 316 of file MainWindow.h.
Definition at line 270 of file MainWindow.h.
Definition at line 266 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 298 of file MainWindow.h.
bool rtabmap::MainWindow::_processingDownloadedMap [private] |
Definition at line 277 of file MainWindow.h.
bool rtabmap::MainWindow::_processingOdometry [private] |
Definition at line 310 of file MainWindow.h.
bool rtabmap::MainWindow::_processingStatistics [private] |
Definition at line 276 of file MainWindow.h.
std::map<int, std::pair<cv::Mat, cv::Mat> > rtabmap::MainWindow::_projectionLocalMaps [private] |
Definition at line 301 of file MainWindow.h.
Definition at line 318 of file MainWindow.h.
QVector<int> rtabmap::MainWindow::_refIds [private] |
Definition at line 331 of file MainWindow.h.
bool rtabmap::MainWindow::_savedMaximized [private] |
Definition at line 285 of file MainWindow.h.
State rtabmap::MainWindow::_state [private] |
Definition at line 261 of file MainWindow.h.
Ui_mainWindow* rtabmap::MainWindow::_ui [private] |
Definition at line 259 of file MainWindow.h.
QStringList rtabmap::MainWindow::_waypoints [private] |
Definition at line 286 of file MainWindow.h.
int rtabmap::MainWindow::_waypointsIndex [private] |
Definition at line 287 of file MainWindow.h.