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,
99 kSrcFlyCapture2 = 101,
100 kSrcStereoImages = 102,
101 kSrcStereoVideo = 103,
117 virtual QString getIniFilePath()
const;
118 virtual QString getTmpIniFilePath()
const;
120 void setCurrentPanelToSource();
121 virtual QString getDefaultWorkingDirectory()
const;
125 void saveWindowGeometry(
const QWidget * window);
126 void loadWindowGeometry(QWidget * window);
127 void saveMainWindowState(
const QMainWindow * mainWindow);
128 void loadMainWindowState(QMainWindow * mainWindow,
bool & maximized,
bool & statusBarShown);
129 void saveWidgetState(
const QWidget * widget);
130 void loadWidgetState(QWidget * widget);
132 void saveCustomConfig(
const QString & section,
const QString & key,
const QString & value);
133 QString loadCustomConfig(
const QString & section,
const QString & key);
136 std::string getParameter(
const std::string & key)
const;
137 void updateParameters(
const ParametersMap & parameters,
bool setOtherParametersToDefault =
false);
140 int getGeneralLoggerLevel()
const;
141 int getGeneralLoggerEventLevel()
const;
142 int getGeneralLoggerPauseLevel()
const;
143 int getGeneralLoggerType()
const;
144 bool getGeneralLoggerPrintTime()
const;
145 bool getGeneralLoggerPrintThreadId()
const;
146 std::vector<std::string> getGeneralLoggerThreads()
const;
147 bool isVerticalLayoutUsed()
const;
148 bool imageRejectedShown()
const;
149 bool imageHighestHypShown()
const;
150 bool beepOnPause()
const;
151 bool isTimeUsedInFigures()
const;
152 bool isCacheSavedInFigures()
const;
153 bool notifyWhenNewGlobalPathIsReceived()
const;
154 int getOdomQualityWarnThr()
const;
155 bool isOdomOnlyInliersShown()
const;
156 bool isPosteriorGraphView()
const;
157 bool isWordsCountGraphView()
const;
158 bool isLocalizationsCountGraphView()
const;
159 int getOdomRegistrationApproach()
const;
160 bool isOdomDisabled()
const;
161 bool isGroundTruthAligned()
const;
163 bool isGraphsShown()
const;
164 bool isLabelsShown()
const;
165 double getVoxel()
const;
166 double getNoiseRadius()
const;
167 int getNoiseMinNeighbors()
const;
168 double getCeilingFilteringHeight()
const;
169 double getFloorFilteringHeight()
const;
170 int getNormalKSearch()
const;
171 double getNormalRadiusSearch()
const;
172 double getScanCeilingFilteringHeight()
const;
173 double getScanFloorFilteringHeight()
const;
174 int getScanNormalKSearch()
const;
175 double getScanNormalRadiusSearch()
const;
176 bool isCloudsShown(
int index)
const;
177 bool isOctomapUpdated()
const;
178 bool isOctomapShown()
const;
179 int getOctomapRenderingType()
const;
180 bool isOctomap2dGrid()
const;
181 int getOctomapTreeDepth()
const;
182 int getOctomapPointSize()
const;
183 int getCloudDecimation(
int index)
const;
184 double getCloudMaxDepth(
int index)
const;
185 double getCloudMinDepth(
int index)
const;
186 std::vector<float> getCloudRoiRatios(
int index)
const;
187 int getCloudColorScheme(
int index)
const;
188 double getCloudOpacity(
int index)
const;
189 int getCloudPointSize(
int index)
const;
191 bool isScansShown(
int index)
const;
192 int getDownsamplingStepScan(
int index)
const;
193 double getScanMaxRange(
int index)
const;
194 double getScanMinRange(
int index)
const;
195 double getCloudVoxelSizeScan(
int index)
const;
196 int getScanColorScheme(
int index)
const;
197 double getScanOpacity(
int index)
const;
198 int getScanPointSize(
int index)
const;
200 bool isFeaturesShown(
int index)
const;
201 bool isFrustumsShown(
int index)
const;
202 int getFeaturesPointSize(
int index)
const;
204 bool isCloudFiltering()
const;
205 bool isSubtractFiltering()
const;
206 double getCloudFilteringRadius()
const;
207 double getCloudFilteringAngle()
const;
208 int getSubtractFilteringMinPts()
const;
209 double getSubtractFilteringRadius()
const;
210 double getSubtractFilteringAngle()
const;
212 bool getGridMapShown()
const;
213 bool isGridMapFrom3DCloud()
const;
214 bool projMapFrame()
const;
215 double projMaxGroundAngle()
const;
216 double projMaxGroundHeight()
const;
217 int projMinClusterSize()
const;
218 double projMaxObstaclesHeight()
const;
219 bool projFlatObstaclesDetected()
const;
220 double getGridMapOpacity()
const;
222 bool isCloudMeshing()
const;
223 double getCloudMeshingAngle()
const;
224 bool isCloudMeshingQuad()
const;
225 bool isCloudMeshingTexture()
const;
226 int getCloudMeshingTriangleSize();
228 QString getWorkingDirectory()
const;
231 double getGeneralInputRate()
const;
232 bool isSourceMirroring()
const;
235 QString getSourceDriverStr()
const;
236 QString getSourceDevice()
const;
238 bool isSourceDatabaseStampsUsed()
const;
239 bool isSourceRGBDColorOnly()
const;
240 bool isDepthFilteringAvailable()
const;
241 QString getSourceDistortionModel()
const;
242 bool isBilateralFiltering()
const;
243 double getBilateralSigmaS()
const;
244 double getBilateralSigmaR()
const;
245 int getSourceImageDecimation()
const;
246 bool isSourceStereoDepthGenerated()
const;
247 bool isSourceStereoExposureCompensation()
const;
248 bool isSourceScanFromDepth()
const;
249 int getSourceScanFromDepthDecimation()
const;
250 double getSourceScanFromDepthMaxDepth()
const;
251 double getSourceScanVoxelSize()
const;
252 int getSourceScanNormalsK()
const;
253 double getSourceScanNormalsRadius()
const;
254 Transform getSourceLocalTransform()
const;
255 Transform getLaserLocalTransform()
const;
257 QString getIMUPath()
const;
258 int getIMURate()
const;
259 Camera * createCamera(
bool useRawImages =
false,
bool useColor =
true);
261 int getIgnoredDCComponents()
const;
264 bool isImagesKept()
const;
265 bool isCloudsKept()
const;
266 float getTimeLimit()
const;
267 float getDetectionRate()
const;
268 bool isSLAMMode()
const;
269 bool isRGBDMode()
const;
270 int getKpMaxFeatures()
const;
273 bool isStatisticsPublished()
const;
274 double getLoopThr()
const;
275 double getVpThr()
const;
276 double getSimThr()
const;
277 int getOdomStrategy()
const;
278 int getOdomBufferSize()
const;
279 QString getCameraInfoDir()
const;
285 void settingsChanged(PreferencesDialog::PANEL_FLAGS);
289 void setInputRate(
double value);
290 void setDetectionRate(
double value);
291 void setTimeLimit(
float value);
292 void setSLAMMode(
bool enabled);
293 void selectSourceDriver(
Src src);
295 void calibrateSimple();
298 void closeDialog ( QAbstractButton * button );
299 void resetApply ( QAbstractButton * button );
300 void resetSettings(
int panelNumber);
301 void loadConfigFrom();
304 void makeObsoleteGeneralPanel();
305 void makeObsoleteCloudRenderingPanel();
306 void makeObsoleteLoggingPanel();
307 void makeObsoleteSourcePanel();
308 void clicked(
const QModelIndex & current,
const QModelIndex & previous);
309 void addParameter(
int value);
310 void addParameter(
bool value);
311 void addParameter(
double value);
312 void addParameter(
const QString & value);
313 void updatePredictionPlot();
315 void updateStereoDisparityVisibility();
316 void useOdomFeatures();
317 void changeWorkingDirectory();
318 void changeDictionaryPath();
319 void changeOdometryORBSLAM2Vocabulary();
320 void changeOdometryOKVISConfigPath();
321 void changeIcpPMConfigPath();
322 void readSettingsEnd();
323 void setupTreeView();
324 void updateBasicParameter();
325 void openDatabaseViewer();
326 void visualizeDistortionModel();
327 void selectSourceDatabase();
328 void selectCalibrationPath();
329 void selectSourceImagesStamps();
330 void selectSourceRGBDImagesPathRGB();
331 void selectSourceRGBDImagesPathDepth();
332 void selectSourceImagesPathScans();
333 void selectSourceImagesPathIMU();
334 void selectSourceImagesPathOdom();
335 void selectSourceImagesPathGt();
336 void selectSourceStereoImagesPathLeft();
337 void selectSourceStereoImagesPathRight();
338 void selectSourceImagesPath();
339 void selectSourceVideoPath();
340 void selectSourceStereoVideoPath();
341 void selectSourceStereoVideoPath2();
342 void selectSourceDistortionModel();
343 void selectSourceOniPath();
344 void selectSourceOni2Path();
345 void selectSourceSvoPath();
346 void updateSourceGrpVisibility();
351 virtual void showEvent ( QShowEvent * event );
352 virtual void closeEvent(QCloseEvent *event);
354 virtual QString getParamMessage();
356 virtual void readGuiSettings(
const QString & filePath = QString());
357 virtual void readCameraSettings(
const QString & filePath = QString());
358 virtual bool readCoreSettings(
const QString & filePath = QString());
360 virtual void writeGuiSettings(
const QString & filePath = QString())
const;
361 virtual void writeCameraSettings(
const QString & filePath = QString())
const;
362 virtual void writeCoreSettings(
const QString & filePath = QString())
const;
364 void setParameter(
const std::string & key,
const std::string & value);
367 void readSettings(
const QString & filePath = QString());
368 void writeSettings(
const QString & filePath = QString());
371 void setupKpRoiPanel();
372 bool parseModel(QList<QGroupBox*> & boxes, QStandardItem * parentItem,
int currentLevel,
int & absoluteIndex);
373 void resetSettings(QGroupBox * groupBox);
374 void addParameter(
const QObject *
object,
int value);
375 void addParameter(
const QObject *
object,
bool value);
376 void addParameter(
const QObject *
object,
double value);
377 void addParameter(
const QObject *
object,
const QString & value);
378 void addParameters(
const QObjectList & children);
379 void addParameters(
const QStackedWidget * stackedWidget,
int panel = -1);
380 void addParameters(
const QGroupBox * box);
381 QList<QGroupBox*> getGroupBoxes();
382 void readSettingsBegin();
390 Ui_preferencesDialog *
_ui;
422 Q_DECLARE_OPERATORS_FOR_FLAGS(PreferencesDialog::PANEL_FLAGS)
QVector< QSpinBox * > _3dRenderingDownsamplingScan
rtabmap::ParametersMap _parameters
void setMonitoringState(bool monitoringState)
CalibrationDialog * _calibrationDialog
QStandardItemModel * _indexModel
std::map< std::string, std::string > ParametersMap
QVector< QSpinBox * > _3dRenderingPtSize
QVector< QDoubleSpinBox * > _3dRenderingVoxelSizeScan
QVector< QCheckBox * > _3dRenderingShowFrustums
QVector< QSpinBox * > _3dRenderingPtSizeFeatures
QVector< QSpinBox * > _3dRenderingPtSizeScan
QVector< QLineEdit * > _3dRenderingRoiRatios
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