28 #ifndef RTABMAP_PREFERENCESDIALOG_H_
29 #define RTABMAP_PREFERENCESDIALOG_H_
31 #include "rtabmap/gui/rtabmap_gui_export.h"
34 #include <QtCore/QModelIndex>
35 #include <QtCore/QVector>
41 class Ui_preferencesDialog;
42 class QAbstractItemModel;
43 class QAbstractButton;
44 class QStandardItemModel;
51 class QProgressDialog;
61 class LoopClosureViewer;
65 class CalibrationDialog;
66 class CreateSimpleCalibrationDialog;
76 kPanelCloudRendering = 2,
79 kPanelCalibration = 16,
83 Q_DECLARE_FLAGS(PANEL_FLAGS, PanelFlag);
92 kSrcOpenNI_CV_ASUS = 3,
104 kSrcFlyCapture2 = 101,
105 kSrcStereoImages = 102,
106 kSrcStereoVideo = 103,
109 kSrcStereoTara = 106,
110 kSrcStereoRealSense2 = 107,
111 kSrcStereoMyntEye = 108,
112 kSrcStereoZedOC = 109,
113 kSrcStereoDepthAI = 110,
123 kSrcLidarVLP16 = 400,
130 virtual QString getIniFilePath()
const;
131 virtual QString getTmpIniFilePath()
const;
132 void init(
const QString & iniFilePath =
"");
133 void setCurrentPanelToSource();
134 virtual QString getDefaultWorkingDirectory()
const;
138 void saveWindowGeometry(
const QWidget * window);
139 void loadWindowGeometry(QWidget * window);
140 void saveMainWindowState(
const QMainWindow * mainWindow);
141 void loadMainWindowState(QMainWindow * mainWindow,
bool & maximized,
bool & statusBarShown);
142 void saveWidgetState(
const QWidget * widget);
143 void loadWidgetState(QWidget * widget);
145 void saveCustomConfig(
const QString & section,
const QString & key,
const QString & value);
146 QString loadCustomConfig(
const QString & section,
const QString & key);
149 std::string getParameter(
const std::string & key)
const;
150 void updateParameters(
const ParametersMap & parameters,
bool setOtherParametersToDefault =
false);
153 int getGeneralLoggerLevel()
const;
154 int getGeneralLoggerEventLevel()
const;
155 int getGeneralLoggerPauseLevel()
const;
156 int getGeneralLoggerType()
const;
157 bool getGeneralLoggerPrintTime()
const;
158 bool getGeneralLoggerPrintThreadId()
const;
159 std::vector<std::string> getGeneralLoggerThreads()
const;
160 bool isVerticalLayoutUsed()
const;
161 bool imageRejectedShown()
const;
162 bool imageHighestHypShown()
const;
163 bool beepOnPause()
const;
164 bool isTimeUsedInFigures()
const;
165 bool isCacheSavedInFigures()
const;
166 bool notifyWhenNewGlobalPathIsReceived()
const;
167 int getOdomQualityWarnThr()
const;
168 bool isOdomOnlyInliersShown()
const;
169 bool isPosteriorGraphView()
const;
170 bool isWordsCountGraphView()
const;
171 bool isLocalizationsCountGraphView()
const;
172 bool isRelocalizationColorOdomCacheGraphView()
const;
173 int getOdomRegistrationApproach()
const;
174 double getOdomF2MGravitySigma()
const;
175 bool isOdomDisabled()
const;
176 bool isOdomSensorAsGt()
const;
177 bool isGroundTruthAligned()
const;
179 bool isGraphsShown()
const;
180 bool isLabelsShown()
const;
181 bool isFramesShown()
const;
182 bool isLandmarksShown()
const;
183 double landmarkVisSize()
const;
184 bool isIMUGravityShown(
int index)
const;
185 double getIMUGravityLength(
int index)
const;
186 bool isIMUAccShown()
const;
187 bool isMarkerDetection()
const;
188 double getMarkerLength()
const;
189 double getVoxel()
const;
190 double getNoiseRadius()
const;
191 int getNoiseMinNeighbors()
const;
192 double getCeilingFilteringHeight()
const;
193 double getFloorFilteringHeight()
const;
194 int getNormalKSearch()
const;
195 double getNormalRadiusSearch()
const;
196 double getScanCeilingFilteringHeight()
const;
197 double getScanFloorFilteringHeight()
const;
198 int getScanNormalKSearch()
const;
199 double getScanNormalRadiusSearch()
const;
200 bool isCloudsShown(
int index)
const;
201 bool isOctomapUpdated()
const;
202 bool isOctomapShown()
const;
203 int getOctomapRenderingType()
const;
204 bool isOctomap2dGrid()
const;
205 int getOctomapTreeDepth()
const;
206 int getOctomapPointSize()
const;
207 int getCloudDecimation(
int index)
const;
208 double getCloudMaxDepth(
int index)
const;
209 double getCloudMinDepth(
int index)
const;
210 std::vector<float> getCloudRoiRatios(
int index)
const;
211 int getCloudColorScheme(
int index)
const;
212 double getCloudOpacity(
int index)
const;
213 int getCloudPointSize(
int index)
const;
215 bool isScansShown(
int index)
const;
216 int getDownsamplingStepScan(
int index)
const;
217 double getScanMaxRange(
int index)
const;
218 double getScanMinRange(
int index)
const;
219 double getCloudVoxelSizeScan(
int index)
const;
220 int getScanColorScheme(
int index)
const;
221 double getScanOpacity(
int index)
const;
222 int getScanPointSize(
int index)
const;
224 bool isFeaturesShown(
int index)
const;
225 bool isFrustumsShown(
int index)
const;
226 int getFeaturesPointSize(
int index)
const;
228 bool isCloudFiltering()
const;
229 bool isSubtractFiltering()
const;
230 double getCloudFilteringRadius()
const;
231 double getCloudFilteringAngle()
const;
232 int getSubtractFilteringMinPts()
const;
233 double getSubtractFilteringRadius()
const;
234 double getSubtractFilteringAngle()
const;
236 double getGridUIResolution()
const;
237 bool getGridMapShown()
const;
238 int getElevationMapShown()
const;
239 int getGridMapSensor()
const;
240 bool projMapFrame()
const;
241 double projMaxGroundAngle()
const;
242 double projMaxGroundHeight()
const;
243 int projMinClusterSize()
const;
244 double projMaxObstaclesHeight()
const;
245 bool projFlatObstaclesDetected()
const;
246 double getGridMapOpacity()
const;
248 bool isCloudMeshing()
const;
249 double getCloudMeshingAngle()
const;
250 bool isCloudMeshingQuad()
const;
251 bool isCloudMeshingTexture()
const;
252 int getCloudMeshingTriangleSize();
254 QString getWorkingDirectory()
const;
257 double getGeneralInputRate()
const;
258 bool isSourceMirroring()
const;
261 QString getSourceDriverStr()
const;
262 QString getSourceDevice()
const;
266 bool isSourceDatabaseStampsUsed()
const;
267 bool isSourceDatabaseStereoToDepth()
const;
268 bool isSourceRGBDColorOnly()
const;
269 int getIMUFilteringStrategy()
const;
270 bool getIMUFilteringBaseFrameConversion()
const;
271 bool isDepthFilteringAvailable()
const;
272 QString getSourceDistortionModel()
const;
273 bool isBilateralFiltering()
const;
274 double getBilateralSigmaS()
const;
275 double getBilateralSigmaR()
const;
276 int getSourceImageDecimation()
const;
277 int getSourceHistogramMethod()
const;
278 bool isSourceFeatureDetection()
const;
279 bool isSourceStereoDepthGenerated()
const;
280 bool isSourceStereoExposureCompensation()
const;
281 bool isRightGrayScale()
const;
282 bool isSourceScanFromDepth()
const;
283 bool isSourceScanDeskewing()
const;
284 int getSourceScanDownsampleStep()
const;
285 double getSourceScanRangeMin()
const;
286 double getSourceScanRangeMax()
const;
287 double getSourceScanVoxelSize()
const;
288 int getSourceScanNormalsK()
const;
289 double getSourceScanNormalsRadius()
const;
290 double getSourceScanForceGroundNormalsUp()
const;
291 Transform getSourceLocalTransform()
const;
292 Transform getLaserLocalTransform()
const;
294 QString getIMUPath()
const;
295 int getIMURate()
const;
296 Camera * createCamera(
bool useRawImages =
false,
bool useColor =
true);
297 SensorCapture * createOdomSensor(
Transform & extrinsics,
double & timeOffset,
float & scaleFactor,
double & waitTime);
298 Lidar * createLidar();
300 int getIgnoredDCComponents()
const;
303 bool isImagesKept()
const;
304 bool isMissingCacheRepublished()
const;
305 bool isCloudsKept()
const;
306 float getTimeLimit()
const;
307 float getDetectionRate()
const;
308 bool isSLAMMode()
const;
309 bool isRGBDMode()
const;
310 int getKpMaxFeatures()
const;
311 bool isPriorIgnored()
const;
314 bool isStatisticsPublished()
const;
315 double getLoopThr()
const;
316 double getVpThr()
const;
317 double getSimThr()
const;
318 int getOdomStrategy()
const;
319 int getOdomBufferSize()
const;
320 QString getCameraInfoDir()
const;
326 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
330 void setInputRate(
double value);
331 void setDetectionRate(
double value);
332 void setTimeLimit(
float value);
333 void setSLAMMode(
bool enabled);
334 void selectSourceDriver(Src src,
int variant = 0);
336 void calibrateSimple();
337 void calibrateOdomSensorExtrinsics();
341 void closeDialog ( QAbstractButton * button );
342 void resetApply ( QAbstractButton * button );
343 void resetSettings(
int panelNumber);
344 void loadConfigFrom();
348 void makeObsoleteGeneralPanel();
349 void makeObsoleteCloudRenderingPanel();
350 void makeObsoleteLoggingPanel();
351 void makeObsoleteSourcePanel();
352 void makeObsoleteCalibrationPanel();
353 void clicked(
const QModelIndex & current,
const QModelIndex & previous);
354 void addParameter(
int value);
355 void addParameter(
bool value);
356 void addParameter(
double value);
357 void addParameter(
const QString & value);
358 void updatePredictionPlot();
360 void updateStereoDisparityVisibility();
361 void updateFeatureMatchingVisibility();
362 void updateGlobalDescriptorVisibility();
363 void updateOdometryStackedIndex(
int index);
364 void useOdomFeatures();
365 void changeWorkingDirectory();
366 void changeDictionaryPath();
367 void changeOdometryORBSLAMVocabulary();
368 void changeOdometryOKVISConfigPath();
369 void changeOdometryVINSConfigPath();
370 void changeOdometryOpenVINSLeftMask();
371 void changeOdometryOpenVINSRightMask();
372 void changeIcpPMConfigPath();
373 void changeSuperPointModelPath();
374 void changePyMatcherPath();
375 void changePyMatcherModel();
376 void changePyDescriptorPath();
377 void changePyDetectorPath();
378 void readSettingsEnd();
379 void setupTreeView();
380 void updateBasicParameter();
381 void openDatabaseViewer();
382 void visualizeDistortionModel();
383 void selectSourceDatabase();
384 void selectCalibrationPath();
385 void selectOdomSensorCalibrationPath();
386 void selectSourceImagesStamps();
387 void selectSourceRGBDImagesPathRGB();
388 void selectSourceRGBDImagesPathDepth();
389 void selectSourceImagesPathScans();
390 void selectSourceImagesPathIMU();
391 void selectSourceImagesPathOdom();
392 void selectSourceImagesPathGt();
393 void selectSourceStereoImagesPathLeft();
394 void selectSourceStereoImagesPathRight();
395 void selectSourceImagesPath();
396 void selectSourceVideoPath();
397 void selectSourceStereoVideoPath();
398 void selectSourceStereoVideoPath2();
399 void selectSourceDistortionModel();
400 void selectSourceOniPath();
401 void selectSourceOni2Path();
402 void selectSourceMKVPath();
403 void selectSourceSvoPath();
404 void selectSourceRealsense2JsonPath();
405 void selectSourceDepthaiBlobPath();
406 void selectVlp16PcapPath();
407 void updateSourceGrpVisibility();
412 virtual void showEvent ( QShowEvent * event );
413 virtual void closeEvent(QCloseEvent *event);
415 virtual QString getParamMessage();
417 virtual void readGuiSettings(
const QString & filePath = QString());
418 virtual void readCameraSettings(
const QString & filePath = QString());
419 virtual bool readCoreSettings(
const QString & filePath = QString());
421 virtual void writeGuiSettings(
const QString & filePath = QString())
const;
422 virtual void writeCameraSettings(
const QString & filePath = QString())
const;
423 virtual void writeCoreSettings(
const QString & filePath = QString())
const;
425 void setParameter(
const std::string & key,
const std::string & value);
428 void readSettings(
const QString & filePath = QString());
429 void writeSettings(
const QString & filePath = QString());
432 void setupKpRoiPanel();
433 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem,
int currentLevel,
int & absoluteIndex);
434 void resetSettings(QGroupBox * groupBox);
435 void loadPreset(
const std::string & presetHexHeader);
436 void addParameter(
const QObject *
object,
int value);
437 void addParameter(
const QObject *
object,
bool value);
438 void addParameter(
const QObject *
object,
double value);
439 void addParameter(
const QObject *
object,
const QString & value);
440 void addParameters(
const QObjectList & children);
441 void addParameters(
const QStackedWidget * stackedWidget,
int panel = -1);
442 void addParameters(
const QGroupBox * box);
443 QList<QGroupBox*> getGroupBoxes();
444 void readSettingsBegin();
445 Camera * createCamera(Src driver,
const QString &
device,
const QString & calibrationPath,
bool useRawImages,
bool useColor,
bool odomOnly,
bool odomSensorExtrinsicsCalib);
453 Ui_preferencesDialog *
_ui;
487 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)