28 #ifndef RTABMAP_PREFERENCESDIALOG_H_ 29 #define RTABMAP_PREFERENCESDIALOG_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;
63 class CalibrationDialog;
64 class CreateSimpleCalibrationDialog;
74 kPanelCloudRendering = 2,
89 kSrcOpenNI_CV_ASUS = 3,
100 kSrcFlyCapture2 = 101,
101 kSrcStereoImages = 102,
102 kSrcStereoVideo = 103,
105 kSrcStereoTara = 106,
106 kSrcStereoRealSense2 = 107,
107 kSrcStereoMyntEye = 108,
108 kSrcStereoZedOC = 109,
109 kSrcStereoDepthAI = 110,
123 virtual QString getIniFilePath()
const;
124 virtual QString getTmpIniFilePath()
const;
125 void init(
const QString & iniFilePath =
"");
126 void setCurrentPanelToSource();
127 virtual QString getDefaultWorkingDirectory()
const;
131 void saveWindowGeometry(
const QWidget * window);
132 void loadWindowGeometry(QWidget * window);
133 void saveMainWindowState(
const QMainWindow * mainWindow);
134 void loadMainWindowState(QMainWindow * mainWindow,
bool & maximized,
bool & statusBarShown);
135 void saveWidgetState(
const QWidget * widget);
136 void loadWidgetState(QWidget * widget);
138 void saveCustomConfig(
const QString & section,
const QString & key,
const QString & value);
139 QString loadCustomConfig(
const QString & section,
const QString & key);
142 std::string getParameter(
const std::string & key)
const;
143 void updateParameters(
const ParametersMap & parameters,
bool setOtherParametersToDefault =
false);
146 int getGeneralLoggerLevel()
const;
147 int getGeneralLoggerEventLevel()
const;
148 int getGeneralLoggerPauseLevel()
const;
149 int getGeneralLoggerType()
const;
150 bool getGeneralLoggerPrintTime()
const;
151 bool getGeneralLoggerPrintThreadId()
const;
152 std::vector<std::string> getGeneralLoggerThreads()
const;
153 bool isVerticalLayoutUsed()
const;
154 bool imageRejectedShown()
const;
155 bool imageHighestHypShown()
const;
156 bool beepOnPause()
const;
157 bool isTimeUsedInFigures()
const;
158 bool isCacheSavedInFigures()
const;
159 bool notifyWhenNewGlobalPathIsReceived()
const;
160 int getOdomQualityWarnThr()
const;
161 bool isOdomOnlyInliersShown()
const;
162 bool isPosteriorGraphView()
const;
163 bool isWordsCountGraphView()
const;
164 bool isLocalizationsCountGraphView()
const;
165 bool isRelocalizationColorOdomCacheGraphView()
const;
166 int getOdomRegistrationApproach()
const;
167 double getOdomF2MGravitySigma()
const;
168 bool isOdomDisabled()
const;
169 bool isOdomSensorAsGt()
const;
170 bool isGroundTruthAligned()
const;
172 bool isGraphsShown()
const;
173 bool isLabelsShown()
const;
174 bool isFramesShown()
const;
175 bool isLandmarksShown()
const;
176 double landmarkVisSize()
const;
177 bool isIMUGravityShown(
int index)
const;
178 double getIMUGravityLength(
int index)
const;
179 bool isIMUAccShown()
const;
180 bool isMarkerDetection()
const;
181 double getMarkerLength()
const;
182 double getVoxel()
const;
183 double getNoiseRadius()
const;
184 int getNoiseMinNeighbors()
const;
185 double getCeilingFilteringHeight()
const;
186 double getFloorFilteringHeight()
const;
187 int getNormalKSearch()
const;
188 double getNormalRadiusSearch()
const;
189 double getScanCeilingFilteringHeight()
const;
190 double getScanFloorFilteringHeight()
const;
191 int getScanNormalKSearch()
const;
192 double getScanNormalRadiusSearch()
const;
193 bool isCloudsShown(
int index)
const;
194 bool isOctomapUpdated()
const;
195 bool isOctomapShown()
const;
196 int getOctomapRenderingType()
const;
197 bool isOctomap2dGrid()
const;
198 int getOctomapTreeDepth()
const;
199 int getOctomapPointSize()
const;
200 int getCloudDecimation(
int index)
const;
201 double getCloudMaxDepth(
int index)
const;
202 double getCloudMinDepth(
int index)
const;
203 std::vector<float> getCloudRoiRatios(
int index)
const;
204 int getCloudColorScheme(
int index)
const;
205 double getCloudOpacity(
int index)
const;
206 int getCloudPointSize(
int index)
const;
208 bool isScansShown(
int index)
const;
209 int getDownsamplingStepScan(
int index)
const;
210 double getScanMaxRange(
int index)
const;
211 double getScanMinRange(
int index)
const;
212 double getCloudVoxelSizeScan(
int index)
const;
213 int getScanColorScheme(
int index)
const;
214 double getScanOpacity(
int index)
const;
215 int getScanPointSize(
int index)
const;
217 bool isFeaturesShown(
int index)
const;
218 bool isFrustumsShown(
int index)
const;
219 int getFeaturesPointSize(
int index)
const;
221 bool isCloudFiltering()
const;
222 bool isSubtractFiltering()
const;
223 double getCloudFilteringRadius()
const;
224 double getCloudFilteringAngle()
const;
225 int getSubtractFilteringMinPts()
const;
226 double getSubtractFilteringRadius()
const;
227 double getSubtractFilteringAngle()
const;
229 bool getGridMapShown()
const;
230 int getGridMapSensor()
const;
231 bool projMapFrame()
const;
232 double projMaxGroundAngle()
const;
233 double projMaxGroundHeight()
const;
234 int projMinClusterSize()
const;
235 double projMaxObstaclesHeight()
const;
236 bool projFlatObstaclesDetected()
const;
237 double getGridMapOpacity()
const;
239 bool isCloudMeshing()
const;
240 double getCloudMeshingAngle()
const;
241 bool isCloudMeshingQuad()
const;
242 bool isCloudMeshingTexture()
const;
243 int getCloudMeshingTriangleSize();
245 QString getWorkingDirectory()
const;
248 double getGeneralInputRate()
const;
249 bool isSourceMirroring()
const;
252 QString getSourceDriverStr()
const;
253 QString getSourceDevice()
const;
256 bool isSourceDatabaseStampsUsed()
const;
257 bool isSourceDatabaseStereoToDepth()
const;
258 bool isSourceRGBDColorOnly()
const;
259 int getIMUFilteringStrategy()
const;
260 bool getIMUFilteringBaseFrameConversion()
const;
261 bool isDepthFilteringAvailable()
const;
262 QString getSourceDistortionModel()
const;
263 bool isBilateralFiltering()
const;
264 double getBilateralSigmaS()
const;
265 double getBilateralSigmaR()
const;
266 int getSourceImageDecimation()
const;
267 bool isSourceStereoDepthGenerated()
const;
268 bool isSourceStereoExposureCompensation()
const;
269 bool isSourceScanFromDepth()
const;
270 int getSourceScanDownsampleStep()
const;
271 double getSourceScanRangeMin()
const;
272 double getSourceScanRangeMax()
const;
273 double getSourceScanVoxelSize()
const;
274 int getSourceScanNormalsK()
const;
275 double getSourceScanNormalsRadius()
const;
276 double getSourceScanForceGroundNormalsUp()
const;
277 Transform getSourceLocalTransform()
const;
278 Transform getLaserLocalTransform()
const;
280 QString getIMUPath()
const;
281 int getIMURate()
const;
282 Camera * createCamera(
bool useRawImages =
false,
bool useColor =
true);
283 Camera * createOdomSensor(
Transform & extrinsics,
double & timeOffset,
float & scaleFactor);
285 int getIgnoredDCComponents()
const;
288 bool isImagesKept()
const;
289 bool isMissingCacheRepublished()
const;
290 bool isCloudsKept()
const;
291 float getTimeLimit()
const;
292 float getDetectionRate()
const;
293 bool isSLAMMode()
const;
294 bool isRGBDMode()
const;
295 int getKpMaxFeatures()
const;
296 bool isPriorIgnored()
const;
299 bool isStatisticsPublished()
const;
300 double getLoopThr()
const;
301 double getVpThr()
const;
302 double getSimThr()
const;
303 int getOdomStrategy()
const;
304 int getOdomBufferSize()
const;
305 QString getCameraInfoDir()
const;
311 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
315 void setInputRate(
double value);
316 void setDetectionRate(
double value);
317 void setTimeLimit(
float value);
318 void setSLAMMode(
bool enabled);
319 void selectSourceDriver(
Src src,
int variant = 0);
321 void calibrateSimple();
322 void calibrateOdomSensorExtrinsics();
325 void closeDialog ( QAbstractButton * button );
326 void resetApply ( QAbstractButton * button );
327 void resetSettings(
int panelNumber);
328 void loadConfigFrom();
331 void makeObsoleteGeneralPanel();
332 void makeObsoleteCloudRenderingPanel();
333 void makeObsoleteLoggingPanel();
334 void makeObsoleteSourcePanel();
335 void clicked(
const QModelIndex & current,
const QModelIndex & previous);
336 void addParameter(
int value);
337 void addParameter(
bool value);
338 void addParameter(
double value);
339 void addParameter(
const QString & value);
340 void updatePredictionPlot();
342 void updateStereoDisparityVisibility();
343 void updateFeatureMatchingVisibility();
344 void updateOdometryStackedIndex(
int index);
345 void useOdomFeatures();
346 void changeWorkingDirectory();
347 void changeDictionaryPath();
348 void changeOdometryORBSLAMVocabulary();
349 void changeOdometryOKVISConfigPath();
350 void changeOdometryVINSConfigPath();
351 void changeIcpPMConfigPath();
352 void changeSuperPointModelPath();
353 void changePyMatcherPath();
354 void changePyMatcherModel();
355 void changePyDetectorPath();
356 void readSettingsEnd();
357 void setupTreeView();
358 void updateBasicParameter();
359 void openDatabaseViewer();
360 void visualizeDistortionModel();
361 void selectSourceDatabase();
362 void selectCalibrationPath();
363 void selectOdomSensorCalibrationPath();
364 void selectSourceImagesStamps();
365 void selectSourceRGBDImagesPathRGB();
366 void selectSourceRGBDImagesPathDepth();
367 void selectSourceImagesPathScans();
368 void selectSourceImagesPathIMU();
369 void selectSourceImagesPathOdom();
370 void selectSourceImagesPathGt();
371 void selectSourceStereoImagesPathLeft();
372 void selectSourceStereoImagesPathRight();
373 void selectSourceImagesPath();
374 void selectSourceVideoPath();
375 void selectSourceStereoVideoPath();
376 void selectSourceStereoVideoPath2();
377 void selectSourceDistortionModel();
378 void selectSourceOniPath();
379 void selectSourceOni2Path();
380 void selectSourceMKVPath();
381 void selectSourceSvoPath();
382 void selectSourceRealsense2JsonPath();
383 void updateSourceGrpVisibility();
388 virtual void showEvent ( QShowEvent * event );
389 virtual void closeEvent(QCloseEvent *event);
391 virtual QString getParamMessage();
393 virtual void readGuiSettings(
const QString & filePath = QString());
394 virtual void readCameraSettings(
const QString & filePath = QString());
395 virtual bool readCoreSettings(
const QString & filePath = QString());
397 virtual void writeGuiSettings(
const QString & filePath = QString())
const;
398 virtual void writeCameraSettings(
const QString & filePath = QString())
const;
399 virtual void writeCoreSettings(
const QString & filePath = QString())
const;
401 void setParameter(
const std::string & key,
const std::string & value);
404 void readSettings(
const QString & filePath = QString());
405 void writeSettings(
const QString & filePath = QString());
408 void setupKpRoiPanel();
409 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem,
int currentLevel,
int & absoluteIndex);
410 void resetSettings(QGroupBox * groupBox);
411 void addParameter(
const QObject *
object,
int value);
412 void addParameter(
const QObject *
object,
bool value);
413 void addParameter(
const QObject *
object,
double value);
414 void addParameter(
const QObject *
object,
const QString & value);
415 void addParameters(
const QObjectList & children);
416 void addParameters(
const QStackedWidget * stackedWidget,
int panel = -1);
417 void addParameters(
const QGroupBox * box);
418 QList<QGroupBox*> getGroupBoxes();
419 void readSettingsBegin();
420 Camera * createCamera(
Src driver,
const QString &
device,
const QString & calibrationPath,
bool useRawImages,
bool useColor,
bool odomOnly,
bool odomSensorExtrinsicsCalib);
428 Ui_preferencesDialog *
_ui;
462 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
QVector< QSpinBox * > _3dRenderingDownsamplingScan
rtabmap::ParametersMap _parameters
void setMonitoringState(bool monitoringState)
CalibrationDialog * _calibrationDialog
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
QStandardItemModel * _indexModel
std::map< std::string, std::string > ParametersMap
QVector< QCheckBox * > _3dRenderingGravity
QVector< QSpinBox * > _3dRenderingPtSize
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
QVector< QCheckBox * > _3dRenderingShowFrustums
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
QVector< QSpinBox * > _3dRenderingPtSizeScan
QVector< QLineEdit * > _3dRenderingRoiRatios
QVector< QDoubleSpinBox * > _3dRenderingGravityLength
Ui_preferencesDialog * _ui
DiscreteDepthDistortionModel RTABMAP_EXP calibrate(const std::map< int, rtabmap::SensorData > &sequence, const std::map< int, rtabmap::Transform > &trajectory, const pcl::PointCloud< pcl::PointXYZ >::Ptr &map, double coneRadius=0.02, double coneStdevThresh=0.03)
QVector< QDoubleSpinBox * > _3dRenderingOpacity
QVector< QSpinBox * > _3dRenderingDecimation
QVector< QDoubleSpinBox * > _3dRenderingMaxDepth
QVector< QCheckBox * > _3dRenderingShowFeatures
QVector< QSpinBox * > _3dRenderingColorSchemeScan
QVector< QDoubleSpinBox * > _3dRenderingOpacityScan
QVector< QDoubleSpinBox * > _3dRenderingMinDepth
PANEL_FLAGS _obsoletePanels
QProgressDialog * _progressDialog
QVector< QDoubleSpinBox * > _3dRenderingMinRange
QVector< QCheckBox * > _3dRenderingShowScans
QVector< QSpinBox * > _3dRenderingColorScheme
QVector< QDoubleSpinBox * > _3dRenderingMaxRange
rtabmap::ParametersMap _modifiedParameters
QVector< QCheckBox * > _3dRenderingShowClouds
CreateSimpleCalibrationDialog * _createCalibrationDialog