28 #ifndef RTABMAP_MAINWINDOW_H_ 29 #define RTABMAP_MAINWINDOW_H_ 34 #include <QMainWindow> 35 #include <QtCore/QSet> 43 #include <pcl/point_cloud.h> 44 #include <pcl/point_types.h> 45 #include <pcl/PolygonMesh.h> 46 #include <pcl/pcl_base.h> 47 #include <pcl/TextureMesh.h> 54 class LoopClosureViewer;
64 class LikelihoodScene;
70 class TwistGridWidget;
71 class ExportCloudsDialog;
72 class ExportBundlerDialog;
73 class PostProcessingDialog;
74 class DepthCalibrationDialog;
77 class MultiSessionLocWidget;
105 QString getWorkingDirectory()
const;
106 void setMonitoringState(
bool pauseChecked =
false);
116 void updateCacheFromDatabase(
const QString & path);
121 virtual void closeEvent(QCloseEvent* event);
122 virtual bool handleEvent(
UEvent* anEvent);
123 virtual void showEvent(QShowEvent* anEvent);
124 virtual void moveEvent(QMoveEvent* anEvent);
125 virtual void resizeEvent(QResizeEvent* anEvent);
126 virtual void keyPressEvent(QKeyEvent *event);
127 virtual bool eventFilter(QObject *obj, QEvent *event);
133 virtual bool closeDatabase();
134 virtual void startDetection();
135 virtual void pauseDetection();
136 virtual void stopDetection();
137 virtual void saveConfigGUI();
138 virtual void downloadAllClouds();
139 virtual void downloadPoseGraph();
140 virtual void clearTheCache();
141 virtual void openHelp();
142 virtual void openPreferences();
143 virtual void openPreferencesSource();
144 virtual void setDefaultViews();
145 virtual void resetOdometry();
146 virtual void triggerNewMap();
147 virtual void deleteMemory();
151 void cancelProgress();
152 void configGUIModified();
154 void notifyNoMoreImages();
155 void printLoopClosureIds();
156 void generateGraphDOT();
157 void exportPosesRaw();
158 void exportPosesRGBDSLAM();
159 void exportPosesRGBDSLAMMotionCapture();
160 void exportPosesRGBDSLAMID();
161 void exportPosesKITTI();
162 void exportPosesTORO();
163 void exportPosesG2O();
165 void exportOctomap();
166 void showPostProcessingDialog();
167 void depthCalibration();
168 void openWorkingDirectory();
169 void updateEditMenu();
172 void selectFreenect();
173 void selectOpenniCv();
174 void selectOpenniCvAsus();
175 void selectOpenni2();
176 void selectFreenect2();
179 void selectRealSense();
180 void selectRealSense2();
181 void selectRealSense2L515();
182 void selectRealSense2Stereo();
183 void selectStereoDC1394();
184 void selectStereoFlyCapture2();
185 void selectStereoZed();
186 void selectStereoZedOC();
187 void selectStereoTara();
188 void selectStereoUsb();
189 void selectMyntEyeS();
190 void selectDepthAIOAKD();
191 void selectDepthAIOAKDLite();
192 void dumpTheMemory();
193 void dumpThePrediction();
195 void sendWaypoints();
197 void postGoal(
const QString & goal);
201 void updateCacheFromDatabase();
202 void anchorCloudsToGroundTruth();
203 void selectScreenCaptureFormat(
bool checked);
204 void takeScreenshot();
205 void updateElapsedTime();
208 void applyPrefSettings(PreferencesDialog::PANEL_FLAGS flags);
210 void processRtabmapEventInit(
int status,
const QString & info);
213 void processRtabmapLabelErrorEvent(
int id,
const QString & label);
214 void processRtabmapGoalStatusEvent(
int status);
215 void changeImgRateSetting();
216 void changeDetectionRateSetting();
217 void changeTimeLimitSetting();
218 void changeMappingMode();
219 void setAspectRatio(
int w,
int h);
220 void setAspectRatio16_9();
221 void setAspectRatio16_10();
222 void setAspectRatio4_3();
223 void setAspectRatio240p();
224 void setAspectRatio360p();
225 void setAspectRatio480p();
226 void setAspectRatio720p();
227 void setAspectRatio1080p();
228 void setAspectRatioCustom();
229 void exportGridMap();
231 void exportBundlerFormat();
234 void dataRecorderDestroyed();
235 void updateNodeVisibility(
int,
bool);
236 void updateGraphView();
240 void statsProcessed();
242 void cameraInfoProcessed();
244 void odometryProcessed();
245 void thresholdsChanged(
int,
int);
247 void rtabmapEventInitReceived(
int status,
const QString & info);
249 void rtabmapEvent3DMapProcessed();
251 void rtabmapLabelErrorReceived(
int id,
const QString & label);
252 void rtabmapGoalStatusEventReceived(
int status);
253 void imgRateChanged(
double);
254 void detectionRateChanged(
double);
255 void timeLimitChanged(
float);
256 void mappingModeChanged(
bool);
257 void noMoreImagesReceived();
258 void loopClosureThrChanged(qreal);
259 void twistReceived(
float x,
float y,
float z,
float roll,
float pitch,
float yaw,
int row,
int col);
262 void update3DMapVisibility(
bool cloudsShown,
bool scansShown);
264 const std::map<int, Transform> & poses,
265 const std::multimap<int, Link> & constraints,
266 const std::map<int, int> & mapIds,
267 const std::map<int, std::string> & labels,
268 const std::map<int, Transform> & groundTruths,
269 const std::map<int, Transform> & odomCachePoses = std::map<int, Transform>(),
270 const std::multimap<int, Link> & odomCacheConstraints = std::multimap<int, Link>(),
271 bool verboseProgress =
false,
272 std::map<std::string, float> * stats = 0);
273 std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> createAndAddCloudToMap(
int nodeId,
const Transform & pose,
int mapId);
274 void createAndAddScanToMap(
int nodeId,
const Transform & pose,
int mapId);
275 void createAndAddFeaturesToMap(
int nodeId,
const Transform & pose,
int mapId);
276 Transform alignPosesToGroundTruth(
const std::map<int, Transform> & poses,
const std::map<int, Transform> & groundTruth);
277 void drawKeypoints(
const std::multimap<int, cv::KeyPoint> & refWords,
const std::multimap<int, cv::KeyPoint> & loopWords);
278 void drawLandmarks(cv::Mat & image,
const Signature & signature);
279 void setupMainLayout(
bool vertical);
280 void updateSelectSourceMenu();
285 QString captureScreen(
bool cacheInRAM =
false,
bool png =
true);
288 Ui_mainWindow *
ui() {
return _ui; }
294 std::map<int, Transform> currentVisiblePosesMap()
const;
297 const std::map<int, std::string> &
currentLabels()
const {
return _currentLabels; }
298 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > &
cachedClouds()
const {
return _cachedClouds; }
299 const std::map<int, LaserScan> &
createdScans()
const {
return _createdScans; }
300 const std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> &
createdFeatures()
const {
return _createdFeatures; }
316 virtual Camera * createCamera(
319 double & odomSensorTimeOffset,
320 float & odomSensorScaleFactor);
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;
const std::multimap< int, Link > & currentLinksMap() const
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
std::set< int > _cachedEmptyClouds
const std::map< int, LaserScan > & createdScans() const
DepthCalibrationDialog * _depthCalibrationDialog
void setNewDatabasePathOutput(const QString &newDatabasePathOutput)
virtual ParametersMap getCustomParameters()
QString _newDatabasePathOutput
const rtabmap::OctoMap * octomap() const
std::map< int, float > _cachedLocalizationsCount
PreferencesDialog * _preferencesDialog
rtabmap::CameraThread * _camera
bool _autoScreenCaptureOdomSync
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)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
std::vector< CameraModel > _rectCameraModels
QMap< int, QString > _exportPosesFileName
const rtabmap::OccupancyGrid * occupancyGrid() const
long _createdCloudsMemoryUsage
const QMap< int, Signature > & cachedSignatures() 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
std::map< int, LaserScan > _createdScans
const QString & newDatabasePathOutput() const
rtabmap::LoopClosureViewer * loopClosureViewer() const
bool isSavedMaximized() const
const State & state() const
rtabmap::OctoMap * _octomap
PdfPlotCurve * _likelihoodCurve
rtabmap::IMUThread * _imuThread
std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > _cachedClouds
std::vector< CameraModel > _rectCameraModelsOdom
std::map< int, std::string > _currentLabels
bool isProcessingOdometry() const
rtabmap::ProgressDialog * progressDialog()
const std::map< int, Transform > & currentPosesMap() const
CloudViewer * _cloudViewer
PdfPlotCurve * _posteriorCurve
bool _autoScreenCaptureRAM
MultiSessionLocWidget * _multiSessionLocWidget
RecoveryProgressState state
std::map< int, Transform > _currentGTPosesMap
const std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > & createdFeatures() const
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
rtabmap::CloudViewer * cloudViewer() const
std::map< int, int > _currentMapIds
const std::map< int, int > & currentMapIds() const
QString _defaultOpenDatabasePath
ProgressDialog * _progressDialog
PostProcessingDialog * _postProcessingDialog
AboutDialog * _aboutDialog
ExportBundlerDialog * _exportBundlerDialog
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
const std::map< int, Transform > & currentGTPosesMap() const
bool _processingStatistics
QString _graphSavingFileName
bool isProcessingStatistics() const
QVector< int > _loopClosureIds
static int newDatabase(BtShared *pBt)
const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > & cachedClouds() const
const std::map< int, std::string > & currentLabels() const
ExportCloudsDialog * _exportCloudsDialog
bool _autoScreenCapturePNG
DataRecorder * _dataRecorder
LoopClosureViewer * _loopClosureViewer
bool isDatabaseUpdated() const
bool _processingDownloadedMap
static int openDatabase(const char *zFilename, sqlite3 **ppDb, unsigned int flags, const char *zVfs)