00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap/core/CameraModel.h>
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UDirectory.h>
00031 #include <rtabmap/utilite/UFile.h>
00032 #include <opencv2/imgproc/imgproc.hpp>
00033
00034 namespace rtabmap {
00035
00036 CameraModel::CameraModel() :
00037 P_(cv::Mat::zeros(3, 4, CV_64FC1))
00038 {
00039
00040 }
00041
00042 CameraModel::CameraModel(const std::string & cameraName, const cv::Size & imageSize, const cv::Mat & K, const cv::Mat & D, const cv::Mat & R, const cv::Mat & P) :
00043 name_(cameraName),
00044 imageSize_(imageSize),
00045 K_(K),
00046 D_(D),
00047 R_(R),
00048 P_(P)
00049 {
00050 UASSERT(!name_.empty());
00051 UASSERT(imageSize_.width > 0 && imageSize_.height > 0);
00052 UASSERT(K_.rows == 3 && K_.cols == 3);
00053 UASSERT(D_.rows == 1 && (D_.cols == 4 || D_.cols == 5 || D_.cols == 8));
00054 UASSERT(R_.rows == 3 && R_.cols == 3);
00055 UASSERT(P_.rows == 3 && P_.cols == 4);
00056
00057
00058 UINFO("Initialize rectify map");
00059 cv::initUndistortRectifyMap(K_, D_, R_, P_, imageSize_, CV_32FC1, mapX_, mapY_);
00060 }
00061
00062 bool CameraModel::load(const std::string & filePath)
00063 {
00064 K_ = cv::Mat();
00065 D_ = cv::Mat();
00066 R_ = cv::Mat();
00067 P_ = cv::Mat::zeros(3, 4, CV_64FC1);
00068 mapX_ = cv::Mat();
00069 mapY_ = cv::Mat();
00070
00071 if(UFile::exists(filePath))
00072 {
00073 UINFO("Reading calibration file \"%s\"", filePath.c_str());
00074 cv::FileStorage fs(filePath, cv::FileStorage::READ);
00075
00076 name_ = (int)fs["camera_name"];
00077 imageSize_.width = (int)fs["image_width"];
00078 imageSize_.height = (int)fs["image_height"];
00079 UASSERT(!name_.empty());
00080 UASSERT(imageSize_.width > 0);
00081 UASSERT(imageSize_.height > 0);
00082
00083
00084 cv::FileNode n = fs["camera_matrix"];
00085 int rows = (int)n["rows"];
00086 int cols = (int)n["cols"];
00087 std::vector<double> data;
00088 n["data"] >> data;
00089 UASSERT(rows*cols == (int)data.size());
00090 UASSERT(rows == 3 && cols == 3);
00091 K_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00092
00093 n = fs["distortion_coefficients"];
00094 rows = (int)n["rows"];
00095 cols = (int)n["cols"];
00096 data.clear();
00097 n["data"] >> data;
00098 UASSERT(rows*cols == (int)data.size());
00099 UASSERT(rows == 1 && (cols == 4 || cols == 5 || cols == 8));
00100 D_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00101
00102 n = fs["rectification_matrix"];
00103 rows = (int)n["rows"];
00104 cols = (int)n["cols"];
00105 data.clear();
00106 n["data"] >> data;
00107 UASSERT(rows*cols == (int)data.size());
00108 UASSERT(rows == 3 && cols == 3);
00109 R_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00110
00111 n = fs["projection_matrix"];
00112 rows = (int)n["rows"];
00113 cols = (int)n["cols"];
00114 data.clear();
00115 n["data"] >> data;
00116 UASSERT(rows*cols == (int)data.size());
00117 UASSERT(rows == 3 && cols == 4);
00118 P_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00119
00120 fs.release();
00121
00122
00123 UINFO("Initialize rectify map");
00124 cv::initUndistortRectifyMap(K_, D_, R_, P_, imageSize_, CV_32FC1, mapX_, mapY_);
00125
00126 return true;
00127 }
00128 return false;
00129 }
00130
00131 bool CameraModel::save(const std::string & filePath)
00132 {
00133 if(!filePath.empty() && !name_.empty() && !K_.empty() && !D_.empty() && !R_.empty() && !P_.empty())
00134 {
00135 UINFO("Saving calibration to file \"%s\"", filePath.c_str());
00136 cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
00137
00138
00139
00140 fs << "camera_name" << name_;
00141 fs << "image_width" << imageSize_.width;
00142 fs << "image_height" << imageSize_.height;
00143
00144 fs << "camera_matrix" << "{";
00145 fs << "rows" << K_.rows;
00146 fs << "cols" << K_.cols;
00147 fs << "data" << std::vector<double>((double*)K_.data, ((double*)K_.data)+(K_.rows*K_.cols));
00148 fs << "}";
00149
00150 fs << "distortion_coefficients" << "{";
00151 fs << "rows" << D_.rows;
00152 fs << "cols" << D_.cols;
00153 fs << "data" << std::vector<double>((double*)D_.data, ((double*)D_.data)+(D_.rows*D_.cols));
00154 fs << "}";
00155
00156 fs << "rectification_matrix" << "{";
00157 fs << "rows" << R_.rows;
00158 fs << "cols" << R_.cols;
00159 fs << "data" << std::vector<double>((double*)R_.data, ((double*)R_.data)+(R_.rows*R_.cols));
00160 fs << "}";
00161
00162 fs << "projection_matrix" << "{";
00163 fs << "rows" << P_.rows;
00164 fs << "cols" << P_.cols;
00165 fs << "data" << std::vector<double>((double*)P_.data, ((double*)P_.data)+(P_.rows*P_.cols));
00166 fs << "}";
00167
00168 fs.release();
00169
00170 return true;
00171 }
00172 return false;
00173 }
00174
00175 cv::Mat CameraModel::rectifyImage(const cv::Mat & raw, int interpolation) const
00176 {
00177 if(!mapX_.empty() && !mapY_.empty())
00178 {
00179 cv::Mat rectified;
00180 cv::remap(raw, rectified, mapX_, mapY_, interpolation);
00181 return rectified;
00182 }
00183 else
00184 {
00185 return raw.clone();
00186 }
00187 }
00188
00189
00190 cv::Mat CameraModel::rectifyDepth(const cv::Mat & raw) const
00191 {
00192 UASSERT(raw.type() == CV_16UC1);
00193 if(!mapX_.empty() && !mapY_.empty())
00194 {
00195 cv::Mat rectified = cv::Mat::zeros(mapX_.rows, mapX_.cols, raw.type());
00196 for(int y=0; y<mapX_.rows; ++y)
00197 {
00198 for(int x=0; x<mapX_.cols; ++x)
00199 {
00200 cv::Point2f pt(mapX_.at<float>(y,x), mapY_.at<float>(y,x));
00201 int xL = (int)floor(pt.x);
00202 int xH = (int)ceil(pt.x);
00203 int yL = (int)floor(pt.y);
00204 int yH = (int)ceil(pt.y);
00205 if(xL >= 0 && yL >= 0 && xH < raw.cols && yH < raw.rows)
00206 {
00207 const unsigned short & pLT = raw.at<unsigned short>(yL, xL);
00208 const unsigned short & pRT = raw.at<unsigned short>(yL, xH);
00209 const unsigned short & pLB = raw.at<unsigned short>(yH, xL);
00210 const unsigned short & pRB = raw.at<unsigned short>(yH, xH);
00211 if(pLT > 0 && pRT > 0 && pLB > 0 && pRB > 0)
00212 {
00213 unsigned short avg = (pLT + pRT + pLB + pRB) / 4;
00214 unsigned short thres = 0.01 * avg;
00215 if( abs(pLT - avg) < thres &&
00216 abs(pRT - avg) < thres &&
00217 abs(pLB - avg) < thres &&
00218 abs(pRB - avg) < thres)
00219 {
00220
00221 float a = pt.x - (float)xL;
00222 float c = pt.y - (float)yL;
00223
00224
00225 rectified.at<unsigned short>(y,x) =
00226 (raw.at<unsigned short>(yL, xL) * (1.f - a) + raw.at<unsigned short>(yL, xH) * a) * (1.f - c) +
00227 (raw.at<unsigned short>(yH, xL) * (1.f - a) + raw.at<unsigned short>(yH, xH) * a) * c;
00228 }
00229 }
00230 }
00231 }
00232 }
00233 return rectified;
00234 }
00235 else
00236 {
00237 return raw.clone();
00238 }
00239 }
00240
00241
00242
00243
00244 bool StereoCameraModel::load(const std::string & directory, const std::string & cameraName)
00245 {
00246 name_ = cameraName;
00247 if(left_.load(directory+"/"+cameraName+"_left.yaml") && right_.load(directory+"/"+cameraName+"_right.yaml"))
00248 {
00249
00250 R_ = cv::Mat();
00251 T_ = cv::Mat();
00252
00253 std::string filePath = directory+"/"+cameraName+"_pose.yaml";
00254 if(UFile::exists(filePath))
00255 {
00256 UINFO("Reading stereo calibration file \"%s\"", filePath.c_str());
00257 cv::FileStorage fs(filePath, cv::FileStorage::READ);
00258
00259 name_ = (int)fs["camera_name"];
00260
00261
00262 cv::FileNode n = fs["rotation_matrix"];
00263 int rows = (int)n["rows"];
00264 int cols = (int)n["cols"];
00265 std::vector<double> data;
00266 n["data"] >> data;
00267 UASSERT(rows*cols == (int)data.size());
00268 UASSERT(rows == 3 && cols == 3);
00269 R_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00270
00271 n = fs["translation_matrix"];
00272 rows = (int)n["rows"];
00273 cols = (int)n["cols"];
00274 data.clear();
00275 n["data"] >> data;
00276 UASSERT(rows*cols == (int)data.size());
00277 UASSERT(rows == 3 && cols == 1);
00278 T_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00279
00280 n = fs["essential_matrix"];
00281 rows = (int)n["rows"];
00282 cols = (int)n["cols"];
00283 data.clear();
00284 n["data"] >> data;
00285 UASSERT(rows*cols == (int)data.size());
00286 UASSERT(rows == 3 && cols == 3);
00287 E_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00288
00289 n = fs["fundamental_matrix"];
00290 rows = (int)n["rows"];
00291 cols = (int)n["cols"];
00292 data.clear();
00293 n["data"] >> data;
00294 UASSERT(rows*cols == (int)data.size());
00295 UASSERT(rows == 3 && cols == 3);
00296 F_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
00297
00298 fs.release();
00299
00300 return true;
00301 }
00302 }
00303 return false;
00304 }
00305 bool StereoCameraModel::save(const std::string & directory, const std::string & cameraName)
00306 {
00307 if(left_.save(directory+"/"+cameraName+"_left.yaml") && right_.save(directory+"/"+cameraName+"_right.yaml"))
00308 {
00309 std::string filePath = directory+"/"+cameraName+"_pose.yaml";
00310 if(!filePath.empty() && !name_.empty() && !R_.empty() && !T_.empty())
00311 {
00312 UINFO("Saving stereo calibration to file \"%s\"", filePath.c_str());
00313 cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
00314
00315
00316
00317 fs << "camera_name" << name_;
00318
00319 fs << "rotation_matrix" << "{";
00320 fs << "rows" << R_.rows;
00321 fs << "cols" << R_.cols;
00322 fs << "data" << std::vector<double>((double*)R_.data, ((double*)R_.data)+(R_.rows*R_.cols));
00323 fs << "}";
00324
00325 fs << "translation_matrix" << "{";
00326 fs << "rows" << T_.rows;
00327 fs << "cols" << T_.cols;
00328 fs << "data" << std::vector<double>((double*)T_.data, ((double*)T_.data)+(T_.rows*T_.cols));
00329 fs << "}";
00330
00331 fs << "essential_matrix" << "{";
00332 fs << "rows" << E_.rows;
00333 fs << "cols" << E_.cols;
00334 fs << "data" << std::vector<double>((double*)E_.data, ((double*)E_.data)+(E_.rows*E_.cols));
00335 fs << "}";
00336
00337 fs << "fundamental_matrix" << "{";
00338 fs << "rows" << F_.rows;
00339 fs << "cols" << F_.cols;
00340 fs << "data" << std::vector<double>((double*)F_.data, ((double*)F_.data)+(F_.rows*F_.cols));
00341 fs << "}";
00342
00343 fs.release();
00344
00345 return true;
00346 }
00347 }
00348 return false;
00349 }
00350
00351 Transform StereoCameraModel::transform() const
00352 {
00353 if(!R_.empty() && !T_.empty())
00354 {
00355 return Transform(
00356 R_.at<double>(0,0), R_.at<double>(0,1), R_.at<double>(0,2), T_.at<double>(0),
00357 R_.at<double>(1,0), R_.at<double>(1,1), R_.at<double>(1,2), T_.at<double>(1),
00358 R_.at<double>(2,0), R_.at<double>(2,1), R_.at<double>(2,2), T_.at<double>(2));
00359 }
00360 return Transform();
00361 }
00362
00363 }