28 #ifndef RTABMAP_MAINWINDOW_H_
29 #define RTABMAP_MAINWINDOW_H_
31 #include "rtabmap/gui/rtabmap_gui_export.h"
34 #include <QMainWindow>
35 #include <QtCore/QSet>
36 #include <QElapsedTimer>
44 #include <pcl/point_cloud.h>
45 #include <pcl/point_types.h>
46 #include <pcl/PolygonMesh.h>
47 #include <pcl/pcl_base.h>
48 #include <pcl/TextureMesh.h>
52 class SensorCaptureThread;
56 class LoopClosureViewer;
66 class LikelihoodScene;
72 class TwistGridWidget;
73 class ExportCloudsDialog;
74 class ExportBundlerDialog;
75 class PostProcessingDialog;
76 class DepthCalibrationDialog;
80 class MultiSessionLocWidget;
108 QString getWorkingDirectory()
const;
109 void setMonitoringState(
bool pauseChecked =
false);
119 void updateCacheFromDatabase(
const QString & path);
124 virtual void closeEvent(QCloseEvent* event);
125 virtual bool handleEvent(
UEvent* anEvent);
126 virtual void showEvent(QShowEvent* anEvent);
127 virtual void moveEvent(QMoveEvent* anEvent);
128 virtual void resizeEvent(QResizeEvent* anEvent);
129 virtual void keyPressEvent(QKeyEvent *event);
130 virtual bool eventFilter(QObject *obj, QEvent *event);
136 virtual bool closeDatabase();
137 virtual void startDetection();
138 virtual void pauseDetection();
139 virtual void stopDetection();
140 virtual void saveConfigGUI();
141 virtual void downloadAllClouds();
142 virtual void downloadPoseGraph();
143 virtual void clearTheCache();
144 virtual void openHelp();
145 virtual void openPreferences();
146 virtual void openPreferencesSource();
147 virtual void setDefaultViews();
148 virtual void resetOdometry();
149 virtual void triggerNewMap();
150 virtual void deleteMemory();
154 void cancelProgress();
155 void configGUIModified();
157 void notifyNoMoreImages();
158 void printLoopClosureIds();
159 void generateGraphDOT();
160 void exportPosesRaw();
161 void exportPosesRGBDSLAM();
162 void exportPosesRGBDSLAMMotionCapture();
163 void exportPosesRGBDSLAMID();
164 void exportPosesKITTI();
165 void exportPosesTORO();
166 void exportPosesG2O();
168 void exportOctomap();
169 void showPostProcessingDialog();
170 void depthCalibration();
171 void openWorkingDirectory();
172 void updateEditMenu();
174 void selectFreenect();
175 void selectOpenniCv();
176 void selectOpenniCvAsus();
177 void selectOpenni2();
178 void selectFreenect2();
181 void selectRealSense();
182 void selectRealSense2();
183 void selectRealSense2L515();
184 void selectRealSense2Stereo();
185 void selectStereoDC1394();
186 void selectStereoFlyCapture2();
187 void selectStereoZed();
188 void selectStereoZedOC();
189 void selectStereoTara();
190 void selectStereoUsb();
191 void selectMyntEyeS();
192 void selectDepthAIOAKD();
193 void selectDepthAIOAKDLite();
194 void selectDepthAIOAKDPro();
195 void selectXvisioSeerSense();
197 void dumpTheMemory();
198 void dumpThePrediction();
200 void sendWaypoints();
202 void postGoal(
const QString & goal);
206 void updateCacheFromDatabase();
207 void anchorCloudsToGroundTruth();
208 void selectScreenCaptureFormat(
bool checked);
209 void takeScreenshot();
210 void updateElapsedTime();
213 void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
215 void processRtabmapEventInit(
int status,
const QString & info);
218 void processRtabmapLabelErrorEvent(
int id,
const QString & label);
219 void processRtabmapGoalStatusEvent(
int status);
220 void changeImgRateSetting();
221 void changeDetectionRateSetting();
222 void changeTimeLimitSetting();
223 void changeMappingMode();
224 void setAspectRatio(
int w,
int h);
225 void setAspectRatio16_9();
226 void setAspectRatio16_10();
227 void setAspectRatio4_3();
228 void setAspectRatio240p();
229 void setAspectRatio360p();
230 void setAspectRatio480p();
231 void setAspectRatio720p();
232 void setAspectRatio1080p();
233 void setAspectRatioCustom();
234 void exportGridMap();
236 void exportBundlerFormat();
239 void dataRecorderDestroyed();
240 void updateNodeVisibility(
int,
bool);
241 void updateGraphView();
245 void statsProcessed();
247 void cameraInfoProcessed();
249 void odometryProcessed();
250 void thresholdsChanged(
int,
int);
252 void rtabmapEventInitReceived(
int status,
const QString & info);
254 void rtabmapEvent3DMapProcessed();
256 void rtabmapLabelErrorReceived(
int id,
const QString & label);
257 void rtabmapGoalStatusEventReceived(
int status);
258 void imgRateChanged(
double);
259 void detectionRateChanged(
double);
260 void timeLimitChanged(
float);
261 void mappingModeChanged(
bool);
262 void noMoreImagesReceived();
263 void loopClosureThrChanged(qreal);
264 void twistReceived(
float x,
float y,
float z,
float roll,
float pitch,
float yaw,
int row,
int col);
267 void update3DMapVisibility(
bool cloudsShown,
bool scansShown);
269 const std::map<int, Transform> & poses,
270 const std::multimap<int, Link> & constraints,
271 const std::map<int, int> & mapIds,
272 const std::map<int, std::string> & labels,
273 const std::map<int, Transform> & groundTruths,
274 const std::map<int, Transform> & odomCachePoses = std::map<int, Transform>(),
275 const std::multimap<int, Link> & odomCacheConstraints = std::multimap<int, Link>(),
276 bool verboseProgress =
false,
277 std::map<std::string, float> * stats = 0);
278 std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(
int nodeId,
const Transform & pose,
int mapId);
279 void createAndAddScanToMap(
int nodeId,
const Transform & pose,
int mapId);
280 void createAndAddFeaturesToMap(
int nodeId,
const Transform & pose,
int mapId);
281 Transform alignPosesToGroundTruth(
const std::map<int, Transform> & poses,
const std::map<int, Transform> & groundTruth);
282 void drawKeypoints(
const std::multimap<int, cv::KeyPoint> & refWords,
const std::multimap<int, cv::KeyPoint> & loopWords);
283 void drawLandmarks(cv::Mat & image,
const Signature & signature);
284 void setupMainLayout(
bool vertical);
285 void updateSelectSourceMenu();
290 QString captureScreen(
bool cacheInRAM =
false,
bool png =
true);
293 Ui_mainWindow *
ui() {
return _ui; }
299 std::map<int, Transform> currentVisiblePosesMap()
const;
302 const std::map<int, std::string> &
currentLabels()
const {
return _currentLabels; }
303 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > &
cachedClouds()
const {
return _cachedClouds; }
304 const std::map<int, LaserScan> &
createdScans()
const {
return _createdScans; }
305 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> &
createdFeatures()
const {
return _createdFeatures; }
323 bool refineNeighborLinks,
324 bool refineLoopClosureLinks,
326 bool detectMoreLoopClosures,
327 double clusterRadius,
337 double sbaRematchFeatures,
338 bool abortIfDataMissing =
true);
384 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> >
_cachedClouds;
387 std::pair<int, std::pair<std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>, pcl::IndicesPtr> >
_previousCloud;