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,
121 virtual QString getIniFilePath()
const;
122 virtual QString getTmpIniFilePath()
const;
124 void setCurrentPanelToSource();
125 virtual QString getDefaultWorkingDirectory()
const;
129 void saveWindowGeometry(
const QWidget * window);
130 void loadWindowGeometry(QWidget * window);
131 void saveMainWindowState(
const QMainWindow * mainWindow);
132 void loadMainWindowState(QMainWindow * mainWindow,
bool & maximized,
bool & statusBarShown);
133 void saveWidgetState(
const QWidget * widget);
134 void loadWidgetState(QWidget * widget);
136 void saveCustomConfig(
const QString & section,
const QString & key,
const QString & value);
137 QString loadCustomConfig(
const QString & section,
const QString & key);
140 std::string getParameter(
const std::string & key)
const;
141 void updateParameters(
const ParametersMap & parameters,
bool setOtherParametersToDefault =
false);
144 int getGeneralLoggerLevel()
const;
145 int getGeneralLoggerEventLevel()
const;
146 int getGeneralLoggerPauseLevel()
const;
147 int getGeneralLoggerType()
const;
148 bool getGeneralLoggerPrintTime()
const;
149 bool getGeneralLoggerPrintThreadId()
const;
150 std::vector<std::string> getGeneralLoggerThreads()
const;
151 bool isVerticalLayoutUsed()
const;
152 bool imageRejectedShown()
const;
153 bool imageHighestHypShown()
const;
154 bool beepOnPause()
const;
155 bool isTimeUsedInFigures()
const;
156 bool isCacheSavedInFigures()
const;
157 bool notifyWhenNewGlobalPathIsReceived()
const;
158 int getOdomQualityWarnThr()
const;
159 bool isOdomOnlyInliersShown()
const;
160 bool isPosteriorGraphView()
const;
161 bool isWordsCountGraphView()
const;
162 bool isLocalizationsCountGraphView()
const;
163 int getOdomRegistrationApproach()
const;
164 double getOdomF2MGravitySigma()
const;
165 bool isOdomDisabled()
const;
166 bool isGroundTruthAligned()
const;
168 bool isGraphsShown()
const;
169 bool isLabelsShown()
const;
170 bool isFramesShown()
const;
171 bool isLandmarksShown()
const;
172 double landmarkVisSize()
const;
173 bool isIMUGravityShown(
int index)
const;
174 double getIMUGravityLength(
int index)
const;
175 bool isIMUAccShown()
const;
176 bool isMarkerDetection()
const;
177 double getMarkerLength()
const;
178 double getVoxel()
const;
179 double getNoiseRadius()
const;
180 int getNoiseMinNeighbors()
const;
181 double getCeilingFilteringHeight()
const;
182 double getFloorFilteringHeight()
const;
183 int getNormalKSearch()
const;
184 double getNormalRadiusSearch()
const;
185 double getScanCeilingFilteringHeight()
const;
186 double getScanFloorFilteringHeight()
const;
187 int getScanNormalKSearch()
const;
188 double getScanNormalRadiusSearch()
const;
189 bool isCloudsShown(
int index)
const;
190 bool isOctomapUpdated()
const;
191 bool isOctomapShown()
const;
192 int getOctomapRenderingType()
const;
193 bool isOctomap2dGrid()
const;
194 int getOctomapTreeDepth()
const;
195 int getOctomapPointSize()
const;
196 int getCloudDecimation(
int index)
const;
197 double getCloudMaxDepth(
int index)
const;
198 double getCloudMinDepth(
int index)
const;
199 std::vector<float> getCloudRoiRatios(
int index)
const;
200 int getCloudColorScheme(
int index)
const;
201 double getCloudOpacity(
int index)
const;
202 int getCloudPointSize(
int index)
const;
204 bool isScansShown(
int index)
const;
205 int getDownsamplingStepScan(
int index)
const;
206 double getScanMaxRange(
int index)
const;
207 double getScanMinRange(
int index)
const;
208 double getCloudVoxelSizeScan(
int index)
const;
209 int getScanColorScheme(
int index)
const;
210 double getScanOpacity(
int index)
const;
211 int getScanPointSize(
int index)
const;
213 bool isFeaturesShown(
int index)
const;
214 bool isFrustumsShown(
int index)
const;
215 int getFeaturesPointSize(
int index)
const;
217 bool isCloudFiltering()
const;
218 bool isSubtractFiltering()
const;
219 double getCloudFilteringRadius()
const;
220 double getCloudFilteringAngle()
const;
221 int getSubtractFilteringMinPts()
const;
222 double getSubtractFilteringRadius()
const;
223 double getSubtractFilteringAngle()
const;
225 bool getGridMapShown()
const;
226 bool isGridMapFrom3DCloud()
const;
227 bool projMapFrame()
const;
228 double projMaxGroundAngle()
const;
229 double projMaxGroundHeight()
const;
230 int projMinClusterSize()
const;
231 double projMaxObstaclesHeight()
const;
232 bool projFlatObstaclesDetected()
const;
233 double getGridMapOpacity()
const;
235 bool isCloudMeshing()
const;
236 double getCloudMeshingAngle()
const;
237 bool isCloudMeshingQuad()
const;
238 bool isCloudMeshingTexture()
const;
239 int getCloudMeshingTriangleSize();
241 QString getWorkingDirectory()
const;
244 double getGeneralInputRate()
const;
245 bool isSourceMirroring()
const;
248 QString getSourceDriverStr()
const;
249 QString getSourceDevice()
const;
251 bool isSourceDatabaseStampsUsed()
const;
252 bool isSourceDatabaseStereoToDepth()
const;
253 bool isSourceRGBDColorOnly()
const;
254 int getIMUFilteringStrategy()
const;
255 bool isDepthFilteringAvailable()
const;
256 QString getSourceDistortionModel()
const;
257 bool isBilateralFiltering()
const;
258 double getBilateralSigmaS()
const;
259 double getBilateralSigmaR()
const;
260 int getSourceImageDecimation()
const;
261 bool isSourceStereoDepthGenerated()
const;
262 bool isSourceStereoExposureCompensation()
const;
263 bool isSourceScanFromDepth()
const;
264 int getSourceScanDownsampleStep()
const;
265 double getSourceScanRangeMin()
const;
266 double getSourceScanRangeMax()
const;
267 double getSourceScanVoxelSize()
const;
268 int getSourceScanNormalsK()
const;
269 double getSourceScanNormalsRadius()
const;
270 double getSourceScanForceGroundNormalsUp()
const;
271 Transform getSourceLocalTransform()
const;
272 Transform getLaserLocalTransform()
const;
274 QString getIMUPath()
const;
275 int getIMURate()
const;
276 Camera * createCamera(
bool useRawImages =
false,
bool useColor =
true);
278 int getIgnoredDCComponents()
const;
281 bool isImagesKept()
const;
282 bool isCloudsKept()
const;
283 float getTimeLimit()
const;
284 float getDetectionRate()
const;
285 bool isSLAMMode()
const;
286 bool isRGBDMode()
const;
287 int getKpMaxFeatures()
const;
288 bool isPriorIgnored()
const;
291 bool isStatisticsPublished()
const;
292 double getLoopThr()
const;
293 double getVpThr()
const;
294 double getSimThr()
const;
295 int getOdomStrategy()
const;
296 int getOdomBufferSize()
const;
297 QString getCameraInfoDir()
const;
303 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
307 void setInputRate(
double value);
308 void setDetectionRate(
double value);
309 void setTimeLimit(
float value);
310 void setSLAMMode(
bool enabled);
311 void selectSourceDriver(
Src src);
313 void calibrateSimple();
316 void closeDialog ( QAbstractButton * button );
317 void resetApply ( QAbstractButton * button );
318 void resetSettings(
int panelNumber);
319 void loadConfigFrom();
322 void makeObsoleteGeneralPanel();
323 void makeObsoleteCloudRenderingPanel();
324 void makeObsoleteLoggingPanel();
325 void makeObsoleteSourcePanel();
326 void clicked(
const QModelIndex & current,
const QModelIndex & previous);
327 void addParameter(
int value);
328 void addParameter(
bool value);
329 void addParameter(
double value);
330 void addParameter(
const QString & value);
331 void updatePredictionPlot();
333 void updateStereoDisparityVisibility();
334 void updateFeatureMatchingVisibility();
335 void useOdomFeatures();
336 void changeWorkingDirectory();
337 void changeDictionaryPath();
338 void changeOdometryORBSLAM2Vocabulary();
339 void changeOdometryOKVISConfigPath();
340 void changeOdometryVINSConfigPath();
341 void changeIcpPMConfigPath();
342 void changeSuperPointModelPath();
343 void changePyMatcherPath();
344 void changePyMatcherModel();
345 void readSettingsEnd();
346 void setupTreeView();
347 void updateBasicParameter();
348 void openDatabaseViewer();
349 void visualizeDistortionModel();
350 void selectSourceDatabase();
351 void selectCalibrationPath();
352 void selectSourceImagesStamps();
353 void selectSourceRGBDImagesPathRGB();
354 void selectSourceRGBDImagesPathDepth();
355 void selectSourceImagesPathScans();
356 void selectSourceImagesPathIMU();
357 void selectSourceImagesPathOdom();
358 void selectSourceImagesPathGt();
359 void selectSourceStereoImagesPathLeft();
360 void selectSourceStereoImagesPathRight();
361 void selectSourceImagesPath();
362 void selectSourceVideoPath();
363 void selectSourceStereoVideoPath();
364 void selectSourceStereoVideoPath2();
365 void selectSourceDistortionModel();
366 void selectSourceOniPath();
367 void selectSourceOni2Path();
368 void selectSourceMKVPath();
369 void selectSourceSvoPath();
370 void selectSourceRealsense2JsonPath();
371 void updateSourceGrpVisibility();
376 virtual void showEvent ( QShowEvent * event );
377 virtual void closeEvent(QCloseEvent *event);
379 virtual QString getParamMessage();
381 virtual void readGuiSettings(
const QString & filePath = QString());
382 virtual void readCameraSettings(
const QString & filePath = QString());
383 virtual bool readCoreSettings(
const QString & filePath = QString());
385 virtual void writeGuiSettings(
const QString & filePath = QString())
const;
386 virtual void writeCameraSettings(
const QString & filePath = QString())
const;
387 virtual void writeCoreSettings(
const QString & filePath = QString())
const;
389 void setParameter(
const std::string & key,
const std::string & value);
392 void readSettings(
const QString & filePath = QString());
393 void writeSettings(
const QString & filePath = QString());
396 void setupKpRoiPanel();
397 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem,
int currentLevel,
int & absoluteIndex);
398 void resetSettings(QGroupBox * groupBox);
399 void addParameter(
const QObject *
object,
int value);
400 void addParameter(
const QObject *
object,
bool value);
401 void addParameter(
const QObject *
object,
double value);
402 void addParameter(
const QObject *
object,
const QString & value);
403 void addParameters(
const QObjectList & children);
404 void addParameters(
const QStackedWidget * stackedWidget,
int panel = -1);
405 void addParameters(
const QGroupBox * box);
406 QList<QGroupBox*> getGroupBoxes();
407 void readSettingsBegin();
415 Ui_preferencesDialog *
_ui;
449 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