CalibrationDialog.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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 #include "rtabmap/gui/CalibrationDialog.h"
00029 #include "ui_calibrationDialog.h"
00030 
00031 #include <opencv2/core/core.hpp>
00032 #include <opencv2/imgproc/imgproc.hpp>
00033 #include <opencv2/calib3d/calib3d.hpp>
00034 #include <opencv2/highgui/highgui.hpp>
00035 
00036 #include <QFileDialog>
00037 #include <QMessageBox>
00038 #include <QCloseEvent>
00039 
00040 #include <rtabmap/core/CameraEvent.h>
00041 #include <rtabmap/gui/UCv2Qt.h>
00042 
00043 #include <rtabmap/utilite/ULogger.h>
00044 
00045 namespace rtabmap {
00046 
00047 #define COUNT_MIN 40
00048 
00049 CalibrationDialog::CalibrationDialog(bool stereo, const QString & savingDirectory, bool switchImages, QWidget * parent) :
00050         QDialog(parent),
00051         stereo_(stereo),
00052         savingDirectory_(savingDirectory),
00053         processingData_(false),
00054         savedCalibration_(false)
00055 {
00056         imagePoints_.resize(2);
00057         imageParams_.resize(2);
00058         imageSize_.resize(2);
00059         stereoImagePoints_.resize(2);
00060         models_.resize(2);
00061 
00062         minIrs_.resize(2);
00063         maxIrs_.resize(2);
00064         minIrs_[0] = 0x0000;
00065         maxIrs_[0] = 0x7fff;
00066         minIrs_[1] = 0x0000;
00067         maxIrs_[1] = 0x7fff;
00068 
00069         qRegisterMetaType<cv::Mat>("cv::Mat");
00070 
00071         ui_ = new Ui_calibrationDialog();
00072         ui_->setupUi(this);
00073 
00074         connect(ui_->pushButton_calibrate, SIGNAL(clicked()), this, SLOT(calibrate()));
00075         connect(ui_->pushButton_restart, SIGNAL(clicked()), this, SLOT(restart()));
00076         connect(ui_->pushButton_save, SIGNAL(clicked()), this, SLOT(save()));
00077         connect(ui_->checkBox_switchImages, SIGNAL(stateChanged(int)), this, SLOT(restart()));
00078 
00079         connect(ui_->spinBox_boardWidth, SIGNAL(valueChanged(int)), this, SLOT(setBoardWidth(int)));
00080         connect(ui_->spinBox_boardHeight, SIGNAL(valueChanged(int)), this, SLOT(setBoardHeight(int)));
00081         connect(ui_->doubleSpinBox_squareSize, SIGNAL(valueChanged(double)), this, SLOT(setSquareSize(double)));
00082 
00083         connect(ui_->buttonBox, SIGNAL(rejected()), this, SLOT(close()));
00084 
00085         ui_->image_view->setFocus();
00086 
00087         ui_->progressBar_count->setMaximum(COUNT_MIN);
00088         ui_->progressBar_count->setFormat("%v");
00089         ui_->progressBar_count_2->setMaximum(COUNT_MIN);
00090         ui_->progressBar_count_2->setFormat("%v");
00091 
00092         ui_->radioButton_raw->setChecked(true);
00093 
00094         ui_->checkBox_switchImages->setChecked(switchImages);
00095 
00096         this->setStereoMode(stereo_);
00097 }
00098 
00099 CalibrationDialog::~CalibrationDialog()
00100 {
00101         this->unregisterFromEventsManager();
00102         delete ui_;
00103 }
00104 
00105 void CalibrationDialog::saveSettings(QSettings & settings, const QString & group) const
00106 {
00107         if(!group.isEmpty())
00108         {
00109                 settings.beginGroup(group);
00110         }
00111         settings.setValue("board_width", ui_->spinBox_boardWidth->value());
00112         settings.setValue("board_height", ui_->spinBox_boardHeight->value());
00113         settings.setValue("board_square_size", ui_->doubleSpinBox_squareSize->value());
00114         settings.setValue("geometry", this->saveGeometry());
00115         if(!group.isEmpty())
00116         {
00117                 settings.endGroup();
00118         }
00119 }
00120 
00121 void CalibrationDialog::loadSettings(QSettings & settings, const QString & group)
00122 {
00123         if(!group.isEmpty())
00124         {
00125                 settings.beginGroup(group);
00126         }
00127         this->setBoardWidth(settings.value("board_width", ui_->spinBox_boardWidth->value()).toInt());
00128         this->setBoardHeight(settings.value("board_height", ui_->spinBox_boardHeight->value()).toInt());
00129         this->setSquareSize(settings.value("board_square_size", ui_->doubleSpinBox_squareSize->value()).toDouble());
00130         QByteArray bytes = settings.value("geometry", QByteArray()).toByteArray();
00131         if(!bytes.isEmpty())
00132         {
00133                 this->restoreGeometry(bytes);
00134         }
00135         if(!group.isEmpty())
00136         {
00137                 settings.endGroup();
00138         }
00139 }
00140 
00141 void CalibrationDialog::setSwitchedImages(bool switched)
00142 {
00143         ui_->checkBox_switchImages->setChecked(switched);
00144 }
00145 
00146 void CalibrationDialog::setStereoMode(bool stereo)
00147 {
00148         this->restart();
00149 
00150         stereo_ = stereo;
00151         ui_->progressBar_x_2->setVisible(stereo_);
00152         ui_->progressBar_y_2->setVisible(stereo_);
00153         ui_->progressBar_size_2->setVisible(stereo_);
00154         ui_->progressBar_skew_2->setVisible(stereo_);
00155         ui_->progressBar_count_2->setVisible(stereo_);
00156         ui_->label_right->setVisible(stereo_);
00157         ui_->image_view_2->setVisible(stereo_);
00158         ui_->label_fx_2->setVisible(stereo_);
00159         ui_->label_fy_2->setVisible(stereo_);
00160         ui_->label_cx_2->setVisible(stereo_);
00161         ui_->label_cy_2->setVisible(stereo_);
00162         ui_->label_error_2->setVisible(stereo_);
00163         ui_->label_baseline->setVisible(stereo_);
00164         ui_->label_baseline_name->setVisible(stereo_);
00165         ui_->lineEdit_K_2->setVisible(stereo_);
00166         ui_->lineEdit_D_2->setVisible(stereo_);
00167         ui_->lineEdit_R_2->setVisible(stereo_);
00168         ui_->lineEdit_P_2->setVisible(stereo_);
00169         ui_->radioButton_stereoRectified->setVisible(stereo_);
00170 }
00171 
00172 void CalibrationDialog::setBoardWidth(int width)
00173 {
00174         if(width != ui_->spinBox_boardWidth->value())
00175         {
00176                 ui_->spinBox_boardWidth->setValue(width);
00177                 this->restart();
00178         }
00179 }
00180 
00181 void CalibrationDialog::setBoardHeight(int height)
00182 {
00183         if(height != ui_->spinBox_boardHeight->value())
00184         {
00185                 ui_->spinBox_boardHeight->setValue(height);
00186                 this->restart();
00187         }
00188 }
00189 
00190 void CalibrationDialog::setSquareSize(double size)
00191 {
00192         if(size != ui_->doubleSpinBox_squareSize->value())
00193         {
00194                 ui_->doubleSpinBox_squareSize->setValue(size);
00195                 this->restart();
00196         }
00197 }
00198 
00199 void CalibrationDialog::closeEvent(QCloseEvent* event)
00200 {
00201         if(!savedCalibration_ && models_[0].isValid() && (!stereo_ || stereoModel_.isValid()))
00202         {
00203                 QMessageBox::StandardButton b = QMessageBox::question(this, tr("Save calibration?"),
00204                                 tr("The camera is calibrated but you didn't "
00205                                    "save the calibration, do you want to save it?"),
00206                                 QMessageBox::Yes | QMessageBox::Ignore | QMessageBox::Cancel, QMessageBox::Yes);
00207                 event->ignore();
00208                 if(b == QMessageBox::Yes)
00209                 {
00210                         if(this->save())
00211                         {
00212                                 event->accept();
00213                         }
00214                 }
00215                 else if(b == QMessageBox::Ignore)
00216                 {
00217                         event->accept();
00218                 }
00219         }
00220         else
00221         {
00222                 event->accept();
00223         }
00224         if(event->isAccepted())
00225         {
00226                 this->unregisterFromEventsManager();
00227         }
00228 }
00229 
00230 void CalibrationDialog::handleEvent(UEvent * event)
00231 {
00232         if(!processingData_)
00233         {
00234                 if(event->getClassName().compare("CameraEvent") == 0)
00235                 {
00236                         rtabmap::CameraEvent * e = (rtabmap::CameraEvent *)event;
00237                         if(e->getCode() == rtabmap::CameraEvent::kCodeImage ||
00238                            e->getCode() == rtabmap::CameraEvent::kCodeImageDepth)
00239                         {
00240                                 processingData_ = true;
00241                                 QMetaObject::invokeMethod(this, "processImages",
00242                                                 Q_ARG(cv::Mat, e->data().image()),
00243                                                 Q_ARG(cv::Mat, e->data().depthOrRightImage()),
00244                                                 Q_ARG(QString, QString(e->cameraName().c_str())));
00245                         }
00246                 }
00247         }
00248 }
00249 
00250 void CalibrationDialog::processImages(const cv::Mat & imageLeft, const cv::Mat & imageRight, const QString & cameraName)
00251 {
00252         processingData_ = true;
00253         if(cameraName_.isEmpty())
00254         {
00255                 cameraName_ = "0000";
00256                 if(!cameraName.isEmpty())
00257                 {
00258                         cameraName_ = cameraName;
00259                 }
00260         }
00261         if(ui_->label_serial->text().isEmpty())
00262         {
00263                 ui_->label_serial->setText(cameraName_);
00264 
00265         }
00266         std::vector<cv::Mat> inputRawImages(2);
00267         if(ui_->checkBox_switchImages->isChecked())
00268         {
00269                 inputRawImages[0] = imageRight;
00270                 inputRawImages[1] = imageLeft;
00271         }
00272         else
00273         {
00274                 inputRawImages[0] = imageLeft;
00275                 inputRawImages[1] = imageRight;
00276         }
00277 
00278         std::vector<cv::Mat> images(2);
00279         images[0] = inputRawImages[0];
00280         images[1] = inputRawImages[1];
00281         imageSize_[0] = images[0].size();
00282         imageSize_[1] = images[1].size();
00283 
00284         bool boardFound[2] = {false};
00285         bool boardAccepted[2] = {false};
00286         bool readyToCalibrate[2] = {false};
00287 
00288         std::vector<std::vector<cv::Point2f> > pointBuf(2);
00289 
00290         for(int id=0; id<(stereo_?2:1); ++id)
00291         {
00292                 cv::Mat viewGray;
00293                 if(!images[id].empty())
00294                 {
00295                         if(images[id].type() == CV_16UC1)
00296                         {
00297                                 //assume IR image: convert to gray scaled
00298                                 const float factor = 255.0f / float((maxIrs_[id] - minIrs_[id]));
00299                                 viewGray = cv::Mat(images[id].rows, images[id].cols, CV_8UC1);
00300                                 for(int i=0; i<images[id].rows; ++i)
00301                                 {
00302                                         for(int j=0; j<images[id].cols; ++j)
00303                                         {
00304                                                 viewGray.at<unsigned char>(i, j) = (unsigned char)std::min(float(std::max(images[id].at<unsigned short>(i,j) - minIrs_[id], 0)) * factor, 255.0f);
00305                                         }
00306                                 }
00307                                 cvtColor(viewGray, images[id], cv::COLOR_GRAY2BGR); // convert to show detected points in color
00308                         }
00309                         else if(images[id].channels() == 3)
00310                         {
00311                                 cvtColor(images[id], viewGray, cv::COLOR_BGR2GRAY);
00312                         }
00313                         else
00314                         {
00315                                 viewGray = images[id];
00316                                 cvtColor(viewGray, images[id], cv::COLOR_GRAY2BGR); // convert to show detected points in color
00317                         }
00318                 }
00319                 else
00320                 {
00321                         UERROR("Image %d is empty!! Should not!", id);
00322                 }
00323 
00324                 minIrs_[id] = 0;
00325                 maxIrs_[id] = 0x7FFF;
00326 
00327                 //Dot it only if not yet calibrated
00328                 if(!ui_->pushButton_save->isEnabled())
00329                 {
00330                         cv::Size boardSize(ui_->spinBox_boardWidth->value(), ui_->spinBox_boardHeight->value());
00331                         if(!viewGray.empty())
00332                         {
00333                                 int flags = CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_NORMALIZE_IMAGE;
00334 
00335                                 if(!viewGray.empty())
00336                                 {
00337                                         int maxScale = viewGray.cols < 640?2:1;
00338                                         for( int scale = 1; scale <= maxScale; scale++ )
00339                                         {
00340                                                 cv::Mat timg;
00341                                                 if( scale == 1 )
00342                                                         timg = viewGray;
00343                                                 else
00344                                                         cv::resize(viewGray, timg, cv::Size(), scale, scale, CV_INTER_CUBIC);
00345                                                 boardFound[id] = cv::findChessboardCorners(timg, boardSize, pointBuf[id], flags);
00346                                                 if(boardFound[id])
00347                                                 {
00348                                                         if( scale > 1 )
00349                                                         {
00350                                                                 cv::Mat cornersMat(pointBuf[id]);
00351                                                                 cornersMat *= 1./scale;
00352                                                         }
00353                                                         break;
00354                                                 }
00355                                         }
00356                                 }
00357                         }
00358 
00359                         if(boardFound[id]) // If done with success,
00360                         {
00361                                 // improve the found corners' coordinate accuracy for chessboard
00362                                 float minSquareDistance = -1.0f;
00363                                 for(unsigned int i=0; i<pointBuf[id].size()-1; ++i)
00364                                 {
00365                                         float d = cv::norm(pointBuf[id][i] - pointBuf[id][i+1]);
00366                                         if(minSquareDistance == -1.0f || minSquareDistance > d)
00367                                         {
00368                                                 minSquareDistance = d;
00369                                         }
00370                                 }
00371                                 float radius = minSquareDistance/2.0f +0.5f;
00372                                 cv::cornerSubPix( viewGray, pointBuf[id], cv::Size(radius, radius), cv::Size(-1,-1),
00373                                                 cv::TermCriteria( CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1 ));
00374 
00375                                 // Draw the corners.
00376                                 cv::drawChessboardCorners(images[id], boardSize, cv::Mat(pointBuf[id]), boardFound[id]);
00377 
00378                                 std::vector<float> params(4,0);
00379                                 getParams(pointBuf[id], boardSize, imageSize_[id], params[0], params[1], params[2], params[3]);
00380 
00381                                 bool addSample = true;
00382                                 for(unsigned int i=0; i<imageParams_[id].size(); ++i)
00383                                 {
00384                                         if(fabs(params[0] - imageParams_[id][i].at(0)) < 0.1 && // x
00385                                                 fabs(params[1] - imageParams_[id][i].at(1)) < 0.1 && // y
00386                                                 fabs(params[2] - imageParams_[id][i].at(2)) < 0.05 && // size
00387                                                 fabs(params[3] - imageParams_[id][i].at(3)) < 0.1) // skew
00388                                         {
00389                                                 addSample = false;
00390                                         }
00391                                 }
00392                                 if(addSample)
00393                                 {
00394                                         boardAccepted[id] = true;
00395 
00396                                         imagePoints_[id].push_back(pointBuf[id]);
00397                                         imageParams_[id].push_back(params);
00398 
00399                                         UINFO("[%d] Added board, total=%d. (x=%f, y=%f, size=%f, skew=%f)", id, (int)imagePoints_[id].size(), params[0], params[1], params[2], params[3]);
00400                                 }
00401 
00402                                 // update statistics
00403                                 std::vector<float> xRange(2, imageParams_[id][0].at(0));
00404                                 std::vector<float> yRange(2, imageParams_[id][0].at(1));
00405                                 std::vector<float> sizeRange(2, imageParams_[id][0].at(2));
00406                                 std::vector<float> skewRange(2, imageParams_[id][0].at(3));
00407                                 for(unsigned int i=1; i<imageParams_[id].size(); ++i)
00408                                 {
00409                                         xRange[0] = imageParams_[id][i].at(0) < xRange[0] ? imageParams_[id][i].at(0) : xRange[0];
00410                                         xRange[1] = imageParams_[id][i].at(0) > xRange[1] ? imageParams_[id][i].at(0) : xRange[1];
00411                                         yRange[0] = imageParams_[id][i].at(1) < yRange[0] ? imageParams_[id][i].at(1) : yRange[0];
00412                                         yRange[1] = imageParams_[id][i].at(1) > yRange[1] ? imageParams_[id][i].at(1) : yRange[1];
00413                                         sizeRange[0] = imageParams_[id][i].at(2) < sizeRange[0] ? imageParams_[id][i].at(2) : sizeRange[0];
00414                                         sizeRange[1] = imageParams_[id][i].at(2) > sizeRange[1] ? imageParams_[id][i].at(2) : sizeRange[1];
00415                                         skewRange[0] = imageParams_[id][i].at(3) < skewRange[0] ? imageParams_[id][i].at(3) : skewRange[0];
00416                                         skewRange[1] = imageParams_[id][i].at(3) > skewRange[1] ? imageParams_[id][i].at(3) : skewRange[1];
00417                                 }
00418                                 //UINFO("Stats [%d]:", id);
00419                                 //UINFO("  Count = %d", (int)imagePoints_[id].size());
00420                                 //UINFO("  x =    [%f -> %f]", xRange[0], xRange[1]);
00421                                 //UINFO("  y =    [%f -> %f]", yRange[0], yRange[1]);
00422                                 //UINFO("  size = [%f -> %f]", sizeRange[0], sizeRange[1]);
00423                                 //UINFO("  skew = [%f -> %f]", skewRange[0], skewRange[1]);
00424 
00425                                 float xGood = xRange[1] - xRange[0];
00426                                 float yGood = yRange[1] - yRange[0];
00427                                 float sizeGood = sizeRange[1] - sizeRange[0];
00428                                 float skewGood = skewRange[1] - skewRange[0];
00429 
00430                                 if(id == 0)
00431                                 {
00432                                         ui_->progressBar_x->setValue(xGood*100);
00433                                         ui_->progressBar_y->setValue(yGood*100);
00434                                         ui_->progressBar_size->setValue(sizeGood*100);
00435                                         ui_->progressBar_skew->setValue(skewGood*100);
00436                                         if((int)imagePoints_[id].size() > ui_->progressBar_count->maximum())
00437                                         {
00438                                                 ui_->progressBar_count->setMaximum((int)imagePoints_[id].size());
00439                                         }
00440                                         ui_->progressBar_count->setValue((int)imagePoints_[id].size());
00441                                 }
00442                                 else
00443                                 {
00444                                         ui_->progressBar_x_2->setValue(xGood*100);
00445                                         ui_->progressBar_y_2->setValue(yGood*100);
00446                                         ui_->progressBar_size_2->setValue(sizeGood*100);
00447                                         ui_->progressBar_skew_2->setValue(skewGood*100);
00448 
00449                                         if((int)imagePoints_[id].size() > ui_->progressBar_count_2->maximum())
00450                                         {
00451                                                 ui_->progressBar_count_2->setMaximum((int)imagePoints_[id].size());
00452                                         }
00453                                         ui_->progressBar_count_2->setValue((int)imagePoints_[id].size());
00454                                 }
00455 
00456                                 if(imagePoints_[id].size() >= COUNT_MIN && xGood > 0.5 && yGood > 0.5 && sizeGood > 0.4 && skewGood > 0.5)
00457                                 {
00458                                         readyToCalibrate[id] = true;
00459                                 }
00460 
00461                                 //update IR values
00462                                 if(inputRawImages[id].type() == CV_16UC1)
00463                                 {
00464                                         //update min max IR if the chessboard was found
00465                                         minIrs_[id] = 0xFFFF;
00466                                         maxIrs_[id] = 0;
00467                                         for(size_t i = 0; i < pointBuf[id].size(); ++i)
00468                                         {
00469                                                 const cv::Point2f &p = pointBuf[id][i];
00470                                                 cv::Rect roi(std::max(0, (int)p.x - 3), std::max(0, (int)p.y - 3), 6, 6);
00471 
00472                                                 roi.width = std::min(roi.width, inputRawImages[id].cols - roi.x);
00473                                                 roi.height = std::min(roi.height, inputRawImages[id].rows - roi.y);
00474 
00475                                                 //find minMax in the roi
00476                                                 double min, max;
00477                                                 cv::minMaxLoc(inputRawImages[id](roi), &min, &max);
00478                                                 if(min < minIrs_[id])
00479                                                 {
00480                                                         minIrs_[id] = min;
00481                                                 }
00482                                                 if(max > maxIrs_[id])
00483                                                 {
00484                                                         maxIrs_[id] = max;
00485                                                 }
00486                                         }
00487                                 }
00488                         }
00489                 }
00490         }
00491 
00492         if(stereo_ && ((boardAccepted[0] && boardFound[1]) || (boardAccepted[1] && boardFound[0])))
00493         {
00494                 stereoImagePoints_[0].push_back(pointBuf[0]);
00495                 stereoImagePoints_[1].push_back(pointBuf[1]);
00496                 UINFO("Add stereo image points (size=%d)", (int)stereoImagePoints_[0].size());
00497         }
00498 
00499         if(!stereo_ && readyToCalibrate[0])
00500         {
00501                 ui_->pushButton_calibrate->setEnabled(true);
00502         }
00503         else if(stereo_ && readyToCalibrate[0] && readyToCalibrate[1] && stereoImagePoints_[0].size())
00504         {
00505                 ui_->pushButton_calibrate->setEnabled(true);
00506         }
00507 
00508         if(ui_->radioButton_rectified->isChecked())
00509         {
00510                 if(models_[0].isValid())
00511                 {
00512                         images[0] = models_[0].rectifyImage(images[0]);
00513                 }
00514                 if(models_[1].isValid())
00515                 {
00516                         images[1] = models_[1].rectifyImage(images[1]);
00517                 }
00518         }
00519         else if(ui_->radioButton_stereoRectified->isChecked() && stereoModel_.isValid())
00520         {
00521                 images[0] = stereoModel_.left().rectifyImage(images[0]);
00522                 images[1] = stereoModel_.right().rectifyImage(images[1]);
00523         }
00524 
00525         if(ui_->checkBox_showHorizontalLines->isChecked())
00526         {
00527                 for(int id=0; id<(stereo_?2:1); ++id)
00528                 {
00529                         int step = imageSize_[id].height/16;
00530                         for(int i=step; i<imageSize_[id].height; i+=step)
00531                         {
00532                                 cv::line(images[id], cv::Point(0, i), cv::Point(imageSize_[id].width, i), CV_RGB(0,255,0));
00533                         }
00534                 }
00535         }
00536 
00537         ui_->label_left->setText(tr("%1x%2").arg(images[0].cols).arg(images[0].rows));
00538 
00539         //show frame
00540         ui_->image_view->setImage(uCvMat2QImage(images[0]).mirrored(ui_->checkBox_mirror->isChecked(), false));
00541         if(stereo_)
00542         {
00543                 ui_->label_right->setText(tr("%1x%2").arg(images[1].cols).arg(images[1].rows));
00544                 ui_->image_view_2->setImage(uCvMat2QImage(images[1]).mirrored(ui_->checkBox_mirror->isChecked(), false));
00545         }
00546         processingData_ = false;
00547 }
00548 
00549 void CalibrationDialog::restart()
00550 {
00551         // restart
00552         savedCalibration_ = false;
00553         imagePoints_[0].clear();
00554         imagePoints_[1].clear();
00555         imageParams_[0].clear();
00556         imageParams_[1].clear();
00557         stereoImagePoints_[0].clear();
00558         stereoImagePoints_[1].clear();
00559         models_[0] = CameraModel();
00560         models_[1] = CameraModel();
00561         stereoModel_ = StereoCameraModel();
00562         cameraName_.clear();
00563         minIrs_[0] = 0x0000;
00564         maxIrs_[0] = 0x7fff;
00565         minIrs_[1] = 0x0000;
00566         maxIrs_[1] = 0x7fff;
00567 
00568         ui_->pushButton_calibrate->setEnabled(false);
00569         ui_->pushButton_save->setEnabled(false);
00570         ui_->radioButton_raw->setChecked(true);
00571         ui_->radioButton_rectified->setEnabled(false);
00572         ui_->radioButton_stereoRectified->setEnabled(false);
00573 
00574         ui_->progressBar_count->reset();
00575         ui_->progressBar_count->setMaximum(COUNT_MIN);
00576         ui_->progressBar_x->reset();
00577         ui_->progressBar_y->reset();
00578         ui_->progressBar_size->reset();
00579         ui_->progressBar_skew->reset();
00580 
00581         ui_->progressBar_count_2->reset();
00582         ui_->progressBar_count_2->setMaximum(COUNT_MIN);
00583         ui_->progressBar_x_2->reset();
00584         ui_->progressBar_y_2->reset();
00585         ui_->progressBar_size_2->reset();
00586         ui_->progressBar_skew_2->reset();
00587 
00588         ui_->label_serial->clear();
00589         ui_->label_fx->setNum(0);
00590         ui_->label_fy->setNum(0);
00591         ui_->label_cx->setNum(0);
00592         ui_->label_cy->setNum(0);
00593         ui_->label_baseline->setNum(0);
00594         ui_->label_error->setNum(0);
00595         ui_->lineEdit_K->clear();
00596         ui_->lineEdit_D->clear();
00597         ui_->lineEdit_R->clear();
00598         ui_->lineEdit_P->clear();
00599         ui_->label_fx_2->setNum(0);
00600         ui_->label_fy_2->setNum(0);
00601         ui_->label_cx_2->setNum(0);
00602         ui_->label_cy_2->setNum(0);
00603         ui_->lineEdit_K_2->clear();
00604         ui_->lineEdit_D_2->clear();
00605         ui_->lineEdit_R_2->clear();
00606         ui_->lineEdit_P_2->clear();
00607 }
00608 
00609 void CalibrationDialog::calibrate()
00610 {
00611         processingData_ = true;
00612         savedCalibration_ = false;
00613 
00614         QMessageBox mb(QMessageBox::Information,
00615                         tr("Calibrating..."),
00616                         tr("Operation in progress..."));
00617         mb.show();
00618         QApplication::processEvents();
00619         uSleep(100); // hack make sure the text in the QMessageBox is shown...
00620         QApplication::processEvents();
00621 
00622         std::vector<std::vector<cv::Point3f> > objectPoints(1);
00623         cv::Size boardSize(ui_->spinBox_boardWidth->value(), ui_->spinBox_boardHeight->value());
00624         float squareSize = ui_->doubleSpinBox_squareSize->value();
00625         // compute board corner positions
00626         for( int i = 0; i < boardSize.height; ++i )
00627                 for( int j = 0; j < boardSize.width; ++j )
00628                         objectPoints[0].push_back(cv::Point3f(float( j*squareSize ), float( i*squareSize ), 0));
00629 
00630         for(int id=0; id<(stereo_?2:1); ++id)
00631         {
00632                 UINFO("Calibrating camera %d (samples=%d)", id, (int)imagePoints_[id].size());
00633 
00634                 objectPoints.resize(imagePoints_[id].size(), objectPoints[0]);
00635 
00636                 //calibrate
00637                 std::vector<cv::Mat> rvecs, tvecs;
00638                 std::vector<float> reprojErrs;
00639                 cv::Mat K, D;
00640                 K = cv::Mat::eye(3,3,CV_64FC1);
00641                 UINFO("calibrate!");
00642                 //Find intrinsic and extrinsic camera parameters
00643                 double rms = cv::calibrateCamera(objectPoints,
00644                                 imagePoints_[id],
00645                                 imageSize_[id],
00646                                 K,
00647                                 D,
00648                                 rvecs,
00649                                 tvecs);
00650 
00651                 UINFO("Re-projection error reported by calibrateCamera: %f", rms);
00652 
00653                 // compute reprojection errors
00654                 std::vector<cv::Point2f> imagePoints2;
00655                 int i, totalPoints = 0;
00656                 double totalErr = 0, err;
00657                 reprojErrs.resize(objectPoints.size());
00658 
00659                 for( i = 0; i < (int)objectPoints.size(); ++i )
00660                 {
00661                         cv::projectPoints( cv::Mat(objectPoints[i]), rvecs[i], tvecs[i], K, D, imagePoints2);
00662                         err = cv::norm(cv::Mat(imagePoints_[id][i]), cv::Mat(imagePoints2), CV_L2);
00663 
00664                         int n = (int)objectPoints[i].size();
00665                         reprojErrs[i] = (float) std::sqrt(err*err/n);
00666                         totalErr        += err*err;
00667                         totalPoints     += n;
00668                 }
00669 
00670                 double totalAvgErr =  std::sqrt(totalErr/totalPoints);
00671 
00672                 UINFO("avg re projection error = %f", totalAvgErr);
00673 
00674                 cv::Mat P(3,4,CV_64FC1);
00675                 P.at<double>(2,3) = 1;
00676                 K.copyTo(P.colRange(0,3).rowRange(0,3));
00677 
00678                 std::cout << "cameraMatrix = " << K << std::endl;
00679                 std::cout << "distCoeffs = " << D << std::endl;
00680                 std::cout << "width = " << imageSize_[id].width << std::endl;
00681                 std::cout << "height = " << imageSize_[id].height << std::endl;
00682 
00683                 models_[id] = CameraModel(cameraName_.toStdString(), imageSize_[id], K, D, cv::Mat::eye(3,3,CV_64FC1), P);
00684 
00685                 if(id == 0)
00686                 {
00687                         ui_->label_fx->setNum(models_[id].fx());
00688                         ui_->label_fy->setNum(models_[id].fy());
00689                         ui_->label_cx->setNum(models_[id].cx());
00690                         ui_->label_cy->setNum(models_[id].cy());
00691                         ui_->label_error->setNum(totalAvgErr);
00692 
00693                         std::stringstream strK, strD, strR, strP;
00694                         strK << models_[id].K();
00695                         strD << models_[id].D();
00696                         strR << models_[id].R();
00697                         strP << models_[id].P();
00698                         ui_->lineEdit_K->setText(strK.str().c_str());
00699                         ui_->lineEdit_D->setText(strD.str().c_str());
00700                         ui_->lineEdit_R->setText(strR.str().c_str());
00701                         ui_->lineEdit_P->setText(strP.str().c_str());
00702                 }
00703                 else
00704                 {
00705                         ui_->label_fx_2->setNum(models_[id].fx());
00706                         ui_->label_fy_2->setNum(models_[id].fy());
00707                         ui_->label_cx_2->setNum(models_[id].cx());
00708                         ui_->label_cy_2->setNum(models_[id].cy());
00709                         ui_->label_error_2->setNum(totalAvgErr);
00710 
00711                         std::stringstream strK, strD, strR, strP;
00712                         strK << models_[id].K();
00713                         strD << models_[id].D();
00714                         strR << models_[id].R();
00715                         strP << models_[id].P();
00716                         ui_->lineEdit_K_2->setText(strK.str().c_str());
00717                         ui_->lineEdit_D_2->setText(strD.str().c_str());
00718                         ui_->lineEdit_R_2->setText(strR.str().c_str());
00719                         ui_->lineEdit_P_2->setText(strP.str().c_str());
00720                 }
00721         }
00722 
00723         if(stereo_ && models_[0].isValid() && models_[1].isValid())
00724         {
00725                 UINFO("stereo calibration (samples=%d)...", (int)stereoImagePoints_[0].size());
00726                 cv::Size imageSize = imageSize_[0].width > imageSize_[1].width?imageSize_[0]:imageSize_[1];
00727                 cv::Mat R, T, E, F;
00728 
00729                 std::vector<std::vector<cv::Point3f> > objectPoints(1);
00730                 cv::Size boardSize(ui_->spinBox_boardWidth->value(), ui_->spinBox_boardHeight->value());
00731                 float squareSize = ui_->doubleSpinBox_squareSize->value();
00732                 // compute board corner positions
00733                 for( int i = 0; i < boardSize.height; ++i )
00734                         for( int j = 0; j < boardSize.width; ++j )
00735                                 objectPoints[0].push_back(cv::Point3f(float( j*squareSize ), float( i*squareSize ), 0));
00736                 objectPoints.resize(stereoImagePoints_[0].size(), objectPoints[0]);
00737 
00738                 // calibrate extrinsic
00739                 double rms = cv::stereoCalibrate(objectPoints, stereoImagePoints_[0], stereoImagePoints_[1],
00740                                                 models_[0].K(), models_[0].D(),
00741                                                 models_[1].K(), models_[1].D(),
00742                                                 imageSize, R, T, E, F,
00743                                                 cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 100, 1e-5),
00744                                                 cv::CALIB_FIX_INTRINSIC);
00745                 UINFO("stereo calibration... done with RMS error=%f", rms);
00746 
00747                 double err = 0;
00748                 int npoints = 0;
00749                 std::vector<cv::Vec3f> lines[2];
00750                 UINFO("Computing avg re-projection error...");
00751                 for(unsigned int i = 0; i < stereoImagePoints_[0].size(); i++ )
00752                 {
00753                         int npt = (int)stereoImagePoints_[0][i].size();
00754                         cv::Mat imgpt[2];
00755                         for(int k = 0; k < 2; k++ )
00756                         {
00757                                 imgpt[k] = cv::Mat(stereoImagePoints_[k][i]);
00758                                 cv::undistortPoints(imgpt[k], imgpt[k], models_[k].K(), models_[k].D(), cv::Mat(), models_[k].K());
00759                                 computeCorrespondEpilines(imgpt[k], k+1, F, lines[k]);
00760                         }
00761                         for(int j = 0; j < npt; j++ )
00762                         {
00763                                 double errij = fabs(stereoImagePoints_[0][i][j].x*lines[1][j][0] +
00764                                                                         stereoImagePoints_[0][i][j].y*lines[1][j][1] + lines[1][j][2]) +
00765                                                            fabs(stereoImagePoints_[1][i][j].x*lines[0][j][0] +
00766                                                                         stereoImagePoints_[1][i][j].y*lines[0][j][1] + lines[0][j][2]);
00767                                 err += errij;
00768                         }
00769                         npoints += npt;
00770                 }
00771                 double totalAvgErr = err/(double)npoints;
00772 
00773                 UINFO("stereo avg re projection error = %f", totalAvgErr);
00774 
00775                 cv::Mat R1, R2, P1, P2, Q;
00776                 cv::Rect validRoi[2];
00777 
00778                 cv::stereoRectify(models_[0].K(), models_[0].D(),
00779                                                 models_[1].K(), models_[1].D(),
00780                                                 imageSize, R, T, R1, R2, P1, P2, Q,
00781                                                 cv::CALIB_ZERO_DISPARITY, 0, imageSize, &validRoi[0], &validRoi[1]);
00782 
00783                 UINFO("Valid ROI1 = %d,%d,%d,%d  ROI2 = %d,%d,%d,%d newImageSize=%d/%d",
00784                                 validRoi[0].x, validRoi[0].y, validRoi[0].width, validRoi[0].height,
00785                                 validRoi[1].x, validRoi[1].y, validRoi[1].width, validRoi[1].height,
00786                                 imageSize.width, imageSize.height);
00787 
00788                 if(imageSize_[0].width == imageSize_[1].width)
00789                 {
00790                         //Stereo, keep new extrinsic projection matrix
00791                         stereoModel_ = StereoCameraModel(
00792                                         cameraName_.toStdString(),
00793                                         imageSize_[0], models_[0].K(), models_[0].D(), R1, P1,
00794                                         imageSize_[1], models_[1].K(), models_[1].D(), R2, P2,
00795                                         R, T, E, F);
00796                 }
00797                 else
00798                 {
00799                         //Kinect
00800                         stereoModel_ = StereoCameraModel(
00801                                         cameraName_.toStdString(),
00802                                         imageSize_[0], models_[0].K(), models_[0].D(), cv::Mat::eye(3,3,CV_64FC1), models_[0].P(),
00803                                         imageSize_[1], models_[1].K(), models_[1].D(), cv::Mat::eye(3,3,CV_64FC1), models_[1].P(),
00804                                         R, T, E, F);
00805                 }
00806 
00807                 std::stringstream strR1, strP1, strR2, strP2;
00808                 strR1 << stereoModel_.left().R();
00809                 strP1 << stereoModel_.left().P();
00810                 strR2 << stereoModel_.right().R();
00811                 strP2 << stereoModel_.right().P();
00812                 ui_->lineEdit_R->setText(strR1.str().c_str());
00813                 ui_->lineEdit_P->setText(strP1.str().c_str());
00814                 ui_->lineEdit_R_2->setText(strR2.str().c_str());
00815                 ui_->lineEdit_P_2->setText(strP2.str().c_str());
00816 
00817                 ui_->label_baseline->setNum(stereoModel_.baseline());
00818                 //ui_->label_error_stereo->setNum(totalAvgErr);
00819         }
00820 
00821         if(stereo_ && stereoModel_.isValid())
00822         {
00823                 ui_->radioButton_rectified->setEnabled(true);
00824                 ui_->radioButton_stereoRectified->setEnabled(true);
00825                 ui_->radioButton_stereoRectified->setChecked(true);
00826                 ui_->pushButton_save->setEnabled(true);
00827         }
00828         else if(models_[0].isValid())
00829         {
00830                 ui_->radioButton_rectified->setEnabled(true);
00831                 ui_->radioButton_rectified->setChecked(true);
00832                 ui_->pushButton_save->setEnabled(!stereo_);
00833         }
00834 
00835         UINFO("End calibration");
00836         processingData_ = false;
00837 }
00838 
00839 bool CalibrationDialog::save()
00840 {
00841         bool saved = false;
00842         processingData_ = true;
00843         if(!stereo_)
00844         {
00845                 UASSERT(models_[0].isValid());
00846                 QString cameraName = models_[0].name().c_str();
00847                 QString filePath = QFileDialog::getSaveFileName(this, tr("Export"), savingDirectory_+"/"+cameraName+".yaml", "*.yaml");
00848 
00849                 if(!filePath.isEmpty())
00850                 {
00851                         if(models_[0].save(filePath.toStdString()))
00852                         {
00853                                 QMessageBox::information(this, tr("Export"), tr("Calibration file saved to \"%1\".").arg(filePath));
00854                                 UINFO("Saved \"%s\"!", filePath.toStdString().c_str());
00855                                 savedCalibration_ = true;
00856                                 saved = true;
00857                         }
00858                         else
00859                         {
00860                                 UERROR("Error saving \"%s\"", filePath.toStdString().c_str());
00861                         }
00862                 }
00863         }
00864         else
00865         {
00866                 UASSERT(stereoModel_.isValid());
00867                 QString cameraName = stereoModel_.name().c_str();
00868                 QString filePath = QFileDialog::getSaveFileName(this, tr("Export"), savingDirectory_ + "/" + cameraName, "*.yaml");
00869                 QString name = QFileInfo(filePath).baseName();
00870                 QString dir = QFileInfo(filePath).absoluteDir().absolutePath();
00871                 if(!name.isEmpty())
00872                 {
00873                         std::string base = (dir+QDir::separator()+name).toStdString();
00874                         std::string leftPath = base+"_left.yaml";
00875                         std::string rightPath = base+"_right.yaml";
00876                         std::string posePath = base+"_pose.yaml";
00877                         if(stereoModel_.save(dir.toStdString(), name.toStdString()))
00878                         {
00879                                 QMessageBox::information(this, tr("Export"), tr("Calibration files saved:\n  \"%1\"\n  \"%2\"\n  \"%3\".").
00880                                                 arg(leftPath.c_str()).arg(rightPath.c_str()).arg(posePath.c_str()));
00881                                 UINFO("Saved \"%s\" and \"%s\"!", leftPath.c_str(), rightPath.c_str());
00882                                 savedCalibration_ = true;
00883                                 saved = true;
00884                         }
00885                         else
00886                         {
00887                                 UERROR("Error saving \"%s\" and \"%s\"", leftPath.c_str(), rightPath.c_str());
00888                         }
00889                 }
00890         }
00891         processingData_ = false;
00892         return saved;
00893 }
00894 
00895 float CalibrationDialog::getArea(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize)
00896 {
00897         //Get 2d image area of the detected checkerboard.
00898         //The projected checkerboard is assumed to be a convex quadrilateral, and the area computed as
00899         //|p X q|/2; see http://mathworld.wolfram.com/Quadrilateral.html.
00900 
00901         cv::Point2f up_left = corners[0];
00902         cv::Point2f up_right = corners[boardSize.width-1];
00903         cv::Point2f down_right = corners[corners.size()-1];
00904         cv::Point2f down_left = corners[corners.size()-boardSize.width];
00905         cv::Point2f a = up_right - up_left;
00906         cv::Point2f b = down_right - up_right;
00907         cv::Point2f c = down_left - down_right;
00908         cv::Point2f p = b + c;
00909         cv::Point2f q = a + b;
00910         return std::fabs(p.x*q.y - p.y*q.x) / 2.0f;
00911 }
00912 
00913 float CalibrationDialog::getSkew(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize)
00914 {
00915    // Get skew for given checkerboard detection.
00916    // Scaled to [0,1], which 0 = no skew, 1 = high skew
00917    // Skew is proportional to the divergence of three outside corners from 90 degrees.
00918 
00919         cv::Point2f up_left = corners[0];
00920         cv::Point2f up_right = corners[boardSize.width-1];
00921         cv::Point2f down_right = corners[corners.size()-1];
00922 
00923 
00924         //  Return angle between lines ab, bc
00925         cv::Point2f ab = up_left - up_right;
00926         cv::Point2f cb = down_right - up_right;
00927         float angle =  std::acos(ab.dot(cb) / (cv::norm(ab) * cv::norm(cb)));
00928 
00929         float r = 2.0f * std::fabs((CV_PI / 2.0f) - angle);
00930         return r > 1.0f?1.0f:r;
00931 }
00932 
00933 // x -> [0, 1] (left, right)
00934 // y -> [0, 1] (top, bottom)
00935 // size -> [0, 1] (small -> big)
00936 // skew -> [0, 1] (low, high)
00937 void CalibrationDialog::getParams(const std::vector<cv::Point2f> & corners, const cv::Size & boardSize, const cv::Size & imageSize,
00938                 float & x, float & y, float & size, float & skew)
00939 {
00940         float area = getArea(corners, boardSize);
00941         size = std::sqrt(area / (imageSize.width * imageSize.height));
00942         skew = getSkew(corners, boardSize);
00943         float meanX = 0.0f;
00944         float meanY = 0.0f;
00945         for(unsigned int i=0; i<corners.size(); ++i)
00946         {
00947                 meanX += corners[i].x;
00948                 meanY += corners[i].y;
00949         }
00950         meanX /= corners.size();
00951         meanY /= corners.size();
00952         x = meanX / imageSize.width;
00953         y = meanY / imageSize.height;
00954 }
00955 
00956 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31