28 #ifndef RTABMAP_MAINWINDOW_H_ 29 #define RTABMAP_MAINWINDOW_H_ 34 #include <QMainWindow> 35 #include <QtCore/QSet> 42 #include <pcl/point_cloud.h> 43 #include <pcl/point_types.h> 44 #include <pcl/PolygonMesh.h> 45 #include <pcl/pcl_base.h> 46 #include <pcl/TextureMesh.h> 53 class LoopClosureViewer;
63 class LikelihoodScene;
69 class TwistGridWidget;
70 class ExportCloudsDialog;
71 class ExportBundlerDialog;
72 class PostProcessingDialog;
73 class DepthCalibrationDialog;
103 QString getWorkingDirectory()
const;
104 void setMonitoringState(
bool pauseChecked =
false);
114 void updateCacheFromDatabase(
const QString & path);
119 virtual void closeEvent(QCloseEvent* event);
120 virtual bool handleEvent(
UEvent* anEvent);
121 virtual void showEvent(QShowEvent* anEvent);
122 virtual void moveEvent(QMoveEvent* anEvent);
123 virtual void resizeEvent(QResizeEvent* anEvent);
124 virtual void keyPressEvent(QKeyEvent *event);
125 virtual bool eventFilter(QObject *obj, QEvent *event);
131 virtual bool closeDatabase();
132 virtual void startDetection();
133 virtual void pauseDetection();
134 virtual void stopDetection();
135 virtual void saveConfigGUI();
136 virtual void downloadAllClouds();
137 virtual void downloadPoseGraph();
138 virtual void clearTheCache();
139 virtual void openHelp();
140 virtual void openPreferences();
141 virtual void openPreferencesSource();
142 virtual void setDefaultViews();
143 virtual void resetOdometry();
144 virtual void triggerNewMap();
145 virtual void deleteMemory();
149 void cancelProgress();
150 void configGUIModified();
152 void notifyNoMoreImages();
153 void printLoopClosureIds();
154 void generateGraphDOT();
155 void exportPosesRaw();
156 void exportPosesRGBDSLAM();
157 void exportPosesRGBDSLAMMotionCapture();
158 void exportPosesKITTI();
159 void exportPosesTORO();
160 void exportPosesG2O();
162 void exportOctomap();
163 void postProcessing();
164 void depthCalibration();
165 void openWorkingDirectory();
166 void updateEditMenu();
169 void selectFreenect();
170 void selectOpenniCv();
171 void selectOpenniCvAsus();
172 void selectOpenni2();
173 void selectFreenect2();
176 void selectRealSense();
177 void selectRealSense2();
178 void selectRealSense2Stereo();
179 void selectStereoDC1394();
180 void selectStereoFlyCapture2();
181 void selectStereoZed();
182 void selectStereoTara();
183 void selectStereoUsb();
184 void selectMyntEyeS();
185 void dumpTheMemory();
186 void dumpThePrediction();
188 void sendWaypoints();
189 void postGoal(
const QString & goal);
192 void updateCacheFromDatabase();
193 void anchorCloudsToGroundTruth();
194 void selectScreenCaptureFormat(
bool checked);
195 void takeScreenshot();
196 void updateElapsedTime();
199 void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
201 void processRtabmapEventInit(
int status,
const QString & info);
204 void processRtabmapLabelErrorEvent(
int id,
const QString & label);
205 void processRtabmapGoalStatusEvent(
int status);
206 void changeImgRateSetting();
207 void changeDetectionRateSetting();
208 void changeTimeLimitSetting();
209 void changeMappingMode();
210 void setAspectRatio(
int w,
int h);
211 void setAspectRatio16_9();
212 void setAspectRatio16_10();
213 void setAspectRatio4_3();
214 void setAspectRatio240p();
215 void setAspectRatio360p();
216 void setAspectRatio480p();
217 void setAspectRatio720p();
218 void setAspectRatio1080p();
219 void setAspectRatioCustom();
220 void exportGridMap();
222 void exportBundlerFormat();
225 void dataRecorderDestroyed();
226 void updateNodeVisibility(
int,
bool);
227 void updateGraphView();
231 void statsProcessed();
233 void cameraInfoProcessed();
235 void odometryProcessed();
236 void thresholdsChanged(
int,
int);
238 void rtabmapEventInitReceived(
int status,
const QString & info);
240 void rtabmapEvent3DMapProcessed();
242 void rtabmapLabelErrorReceived(
int id,
const QString & label);
243 void rtabmapGoalStatusEventReceived(
int status);
244 void imgRateChanged(
double);
245 void detectionRateChanged(
double);
246 void timeLimitChanged(
float);
247 void mappingModeChanged(
bool);
248 void noMoreImagesReceived();
249 void loopClosureThrChanged(qreal);
250 void twistReceived(
float x,
float y,
float z,
float roll,
float pitch,
float yaw,
int row,
int col);
253 void update3DMapVisibility(
bool cloudsShown,
bool scansShown);
255 const std::map<int, Transform> & poses,
256 const std::multimap<int, Link> & constraints,
257 const std::map<int, int> & mapIds,
258 const std::map<int, std::string> & labels,
259 const std::map<int, Transform> & groundTruths,
260 bool verboseProgress =
false,
261 std::map<std::string, float> * stats = 0);
262 std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(
int nodeId,
const Transform & pose,
int mapId);
263 void createAndAddScanToMap(
int nodeId,
const Transform & pose,
int mapId);
264 void createAndAddFeaturesToMap(
int nodeId,
const Transform & pose,
int mapId);
265 Transform alignPosesToGroundTruth(
const std::map<int, Transform> & poses,
const std::map<int, Transform> & groundTruth);
266 void drawKeypoints(
const std::multimap<int, cv::KeyPoint> & refWords,
const std::multimap<int, cv::KeyPoint> & loopWords);
267 void drawLandmarks(cv::Mat & image,
const Signature & signature);
268 void setupMainLayout(
bool vertical);
269 void updateSelectSourceMenu();
274 QString captureScreen(
bool cacheInRAM =
false,
bool png =
true);
277 Ui_mainWindow *
ui() {
return _ui; }
285 const std::map<int, std::string> &
currentLabels()
const {
return _currentLabels; }
286 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > &
cachedClouds()
const {
return _cachedClouds; }
287 const std::map<int, LaserScan> &
createdScans()
const {
return _createdScans; }
288 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> &
createdFeatures()
const {
return _createdFeatures; }
304 virtual Camera* createCamera();
349 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> >
_cachedClouds;
352 std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> >
_previousCloud;
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & createdFeatures() const
std::set< int > _cachedEmptyClouds
bool isProcessingOdometry() const
bool isDatabaseUpdated() const
DepthCalibrationDialog * _depthCalibrationDialog
void setNewDatabasePathOutput(const QString &newDatabasePathOutput)
virtual ParametersMap getCustomParameters()
QString _newDatabasePathOutput
std::map< int, float > _cachedLocalizationsCount
PreferencesDialog * _preferencesDialog
const std::map< int, LaserScan > & createdScans() const
const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > & cachedClouds() const
rtabmap::CameraThread * _camera
bool _autoScreenCaptureOdomSync
const rtabmap::OctoMap * octomap() const
const std::map< int, Transform > & currentGTPosesMap() const
std::multimap< int, Link > _currentLinksMap
QString _openedDatabasePath
rtabmap::OdometryThread * _odomThread
std::map< std::string, std::string > ParametersMap
GLM_FUNC_DECL genType::row_type row(genType const &m, length_t const &index)
rtabmap::LoopClosureViewer * loopClosureViewer() const
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
std::vector< CameraModel > _rectCameraModels
QMap< int, QString > _exportPosesFileName
long _createdCloudsMemoryUsage
bool isProcessingStatistics() const
const State & state() const
std::map< int, Transform > _currentPosesMap
Transform _odometryCorrection
std::pair< int, std::pair< std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr >, pcl::IndicesPtr > > _previousCloud
const QMap< int, Signature > & cachedSignatures() const
std::map< int, LaserScan > _createdScans
const std::map< int, Transform > & currentPosesMap() const
rtabmap::OctoMap * _octomap
const QString & newDatabasePathOutput() const
PdfPlotCurve * _likelihoodCurve
rtabmap::IMUThread * _imuThread
const std::map< int, std::string > & currentLabels() const
std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > _cachedClouds
const std::multimap< int, Link > & currentLinksMap() const
std::map< int, std::string > _currentLabels
rtabmap::ProgressDialog * progressDialog()
bool isSavedMaximized() const
CloudViewer * _cloudViewer
PdfPlotCurve * _posteriorCurve
bool _autoScreenCaptureRAM
RecoveryProgressState state
std::map< int, Transform > _currentGTPosesMap
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > _createdFeatures
QMap< int, Signature > _cachedSignatures
QMap< QString, QByteArray > _autoScreenCaptureCachedImages
PdfPlotCurve * _rawLikelihoodCurve
rtabmap::OccupancyGrid * _occupancyGrid
std::map< int, float > _cachedWordsCount
std::map< int, int > _currentMapIds
QString _defaultOpenDatabasePath
ProgressDialog * _progressDialog
PostProcessingDialog * _postProcessingDialog
AboutDialog * _aboutDialog
ExportBundlerDialog * _exportBundlerDialog
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
bool _processingStatistics
QString _graphSavingFileName
QVector< int > _loopClosureIds
static int newDatabase(BtShared *pBt)
ExportCloudsDialog * _exportCloudsDialog
bool _autoScreenCapturePNG
const std::map< int, int > & currentMapIds() const
DataRecorder * _dataRecorder
LoopClosureViewer * _loopClosureViewer
rtabmap::CloudViewer * cloudViewer() const
const rtabmap::OccupancyGrid * occupancyGrid() const
bool _processingDownloadedMap
static int openDatabase(const char *zFilename, sqlite3 **ppDb, unsigned int flags, const char *zVfs)