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 exportPosesKITTI();
158 void exportPosesTORO();
159 void exportPosesG2O();
161 void exportOctomap();
162 void postProcessing();
163 void depthCalibration();
164 void openWorkingDirectory();
165 void updateEditMenu();
168 void selectFreenect();
169 void selectOpenniCv();
170 void selectOpenniCvAsus();
171 void selectOpenni2();
172 void selectFreenect2();
174 void selectRealSense();
175 void selectRealSense2();
176 void selectStereoDC1394();
177 void selectStereoFlyCapture2();
178 void selectStereoZed();
179 void selectStereoUsb();
180 void dumpTheMemory();
181 void dumpThePrediction();
183 void sendWaypoints();
184 void postGoal(
const QString & goal);
187 void updateCacheFromDatabase();
188 void anchorCloudsToGroundTruth();
189 void selectScreenCaptureFormat(
bool checked);
190 void takeScreenshot();
191 void updateElapsedTime();
194 void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
196 void processRtabmapEventInit(
int status,
const QString & info);
199 void processRtabmapLabelErrorEvent(
int id,
const QString & label);
200 void processRtabmapGoalStatusEvent(
int status);
201 void changeImgRateSetting();
202 void changeDetectionRateSetting();
203 void changeTimeLimitSetting();
204 void changeMappingMode();
205 void setAspectRatio(
int w,
int h);
206 void setAspectRatio16_9();
207 void setAspectRatio16_10();
208 void setAspectRatio4_3();
209 void setAspectRatio240p();
210 void setAspectRatio360p();
211 void setAspectRatio480p();
212 void setAspectRatio720p();
213 void setAspectRatio1080p();
214 void setAspectRatioCustom();
215 void exportGridMap();
217 void exportBundlerFormat();
220 void dataRecorderDestroyed();
221 void updateNodeVisibility(
int,
bool);
222 void updateGraphView();
226 void statsProcessed();
228 void cameraInfoProcessed();
230 void odometryProcessed();
231 void thresholdsChanged(
int,
int);
233 void rtabmapEventInitReceived(
int status,
const QString & info);
235 void rtabmapEvent3DMapProcessed();
237 void rtabmapLabelErrorReceived(
int id,
const QString & label);
238 void rtabmapGoalStatusEventReceived(
int status);
239 void imgRateChanged(
double);
240 void detectionRateChanged(
double);
241 void timeLimitChanged(
float);
242 void mappingModeChanged(
bool);
243 void noMoreImagesReceived();
244 void loopClosureThrChanged(
float);
245 void twistReceived(
float x,
float y,
float z,
float roll,
float pitch,
float yaw,
int row,
int col);
248 void update3DMapVisibility(
bool cloudsShown,
bool scansShown);
250 const std::map<int, Transform> & poses,
251 const std::multimap<int, Link> & constraints,
252 const std::map<int, int> & mapIds,
253 const std::map<int, std::string> & labels,
254 const std::map<int, Transform> & groundTruths,
255 bool verboseProgress =
false,
256 std::map<std::string, float> * stats = 0);
257 std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(
int nodeId,
const Transform & pose,
int mapId);
258 void createAndAddScanToMap(
int nodeId,
const Transform & pose,
int mapId);
259 void createAndAddFeaturesToMap(
int nodeId,
const Transform & pose,
int mapId);
260 Transform alignPosesToGroundTruth(
const std::map<int, Transform> & poses,
const std::map<int, Transform> & groundTruth);
261 void drawKeypoints(
const std::multimap<int, cv::KeyPoint> & refWords,
const std::multimap<int, cv::KeyPoint> & loopWords);
262 void setupMainLayout(
bool vertical);
263 void updateSelectSourceMenu();
268 QString captureScreen(
bool cacheInRAM =
false,
bool png =
true);
271 Ui_mainWindow *
ui() {
return _ui; }
279 const std::map<int, std::string> &
currentLabels()
const {
return _currentLabels; }
280 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > &
cachedClouds()
const {
return _cachedClouds; }
281 const std::map<int, LaserScan> &
createdScans()
const {
return _createdScans; }
282 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> &
createdFeatures()
const {
return _createdFeatures; }
339 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> >
_cachedClouds;
342 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
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), bool g2oRobust=false)
void setNewDatabasePathOutput(const QString &newDatabasePathOutput)
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
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)