CalibrationDialog.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef RTABMAP_CALIBRATIONDIALOG_H_
00029 #define RTABMAP_CALIBRATIONDIALOG_H_
00030 
00031 #include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
00032 
00033 #include <QDialog>
00034 #include <QSettings>
00035 #include <opencv2/opencv.hpp>
00036 
00037 #include <rtabmap/core/CameraModel.h>
00038 #include <rtabmap/core/StereoCameraModel.h>
00039 
00040 #include <rtabmap/utilite/UEventsHandler.h>
00041 
00042 class Ui_calibrationDialog;
00043 
00044 namespace rtabmap {
00045 
00046 class RTABMAPGUI_EXP CalibrationDialog  : public QDialog, public UEventsHandler
00047 {
00048         Q_OBJECT;
00049 
00050 public:
00051         CalibrationDialog(bool stereo = false, const QString & savingDirectory = ".", bool switchImages = false, QWidget * parent = 0);
00052         virtual ~CalibrationDialog();
00053 
00054         bool isCalibrated() const {return models_[0].isValidForProjection() && (stereo_?models_[1].isValidForProjection():true);}
00055         const rtabmap::CameraModel & getLeftCameraModel() const {return models_[0];}
00056         const rtabmap::CameraModel & getRightCameraModel() const {return models_[1];}
00057         const rtabmap::StereoCameraModel & getStereoCameraModel() const {return stereoModel_;}
00058         bool isProcessing() const {return processingData_;}
00059         int getStereoPairs() const {return (int)stereoImagePoints_[0].size();}
00060 
00061         void saveSettings(QSettings & settings, const QString & group = "") const;
00062         void loadSettings(QSettings & settings, const QString & group = "");
00063         void resetSettings();
00064 
00065         void setCameraName(const QString & name);
00066         void setProgressVisibility(bool visible);
00067         void setSwitchedImages(bool switched);
00068         void setStereoMode(bool stereo, const QString & leftSuffix = "left", const QString & rightSuffix = "right");
00069         void setSavingDirectory(const QString & savingDirectory) {savingDirectory_ = savingDirectory;}
00070 
00071         StereoCameraModel stereoCalibration(const CameraModel & left, const CameraModel & right, bool ignoreStereoRectification) const;
00072 
00073 public Q_SLOTS:
00074         void setBoardWidth(int width);
00075         void setBoardHeight(int height);
00076         void setSquareSize(double size);
00077         void setMaxScale(int scale);
00078 
00079         void processImages(const cv::Mat & imageLeft, const cv::Mat & imageRight, const QString & cameraName);
00080         void calibrate();
00081         void restart();
00082         bool save();
00083 
00084 private Q_SLOTS:
00085         void unlock();
00086 
00087 protected:
00088         virtual void closeEvent(QCloseEvent* event);
00089         virtual bool handleEvent(UEvent * event);
00090 
00091 private:
00092         float getArea(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize);
00093         float getSkew(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize);
00094 
00095         // x -> [0, 1] (left, right)
00096         // y -> [0, 1] (top, bottom)
00097         // size -> [0, 1] (small -> big)
00098         // skew -> [0, 1] (low, high)
00099         void getParams(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize, const cv::Size & imageSize,
00100                         float & x, float & y, float & size, float & skew);
00101 
00102 private:
00103         // parameters
00104         bool stereo_;
00105         QString leftSuffix_;
00106         QString rightSuffix_;
00107         QString savingDirectory_;
00108 
00109         QString cameraName_;
00110         bool processingData_;
00111         bool savedCalibration_;
00112 
00113         std::vector<std::vector<std::vector<cv::Point2f> > > imagePoints_;
00114         std::vector<std::vector<std::vector<float> > > imageParams_;
00115         std::vector<std::vector<std::vector<cv::Point2f> > > stereoImagePoints_;
00116         std::vector<cv::Size > imageSize_;
00117         std::vector<rtabmap::CameraModel> models_;
00118         rtabmap::StereoCameraModel stereoModel_;
00119         std::vector<unsigned short> minIrs_;
00120         std::vector<unsigned short> maxIrs_;
00121 
00122         Ui_calibrationDialog * ui_;
00123 };
00124 
00125 } /* namespace rtabmap */
00126 #endif /* CALIBRATIONDIALOG_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:18