35 #include <opencv2/imgproc/imgproc.hpp> 45 const std::string & cameraName,
60 UASSERT(
K_.empty() || (
K_.rows == 3 &&
K_.cols == 3 &&
K_.type() == CV_64FC1));
61 UASSERT(
D_.empty() || (
D_.rows == 1 && (
D_.cols == 4 ||
D_.cols == 5 ||
D_.cols == 6 ||
D_.cols == 8) &&
D_.type() == CV_64FC1));
62 UASSERT(
R_.empty() || (
R_.rows == 3 &&
R_.cols == 3 &&
R_.type() == CV_64FC1));
63 UASSERT(
P_.empty() || (
P_.rows == 3 &&
P_.cols == 4 &&
P_.type() == CV_64FC1));
75 K_(
cv::Mat::eye(3, 3, CV_64FC1)),
80 UASSERT_MSG(cx >= 0.0 && imageSize.width>=0,
uFormat(
"cx=%f imageSize.width=%d", cx, imageSize.width).c_str());
81 UASSERT_MSG(cy >= 0.0 && imageSize.height>=0,
uFormat(
"cy=%f imageSize.height=%d", cy, imageSize.height).c_str());
84 if(cx==0.0 && imageSize.width > 0)
86 cx = double(imageSize.width)/2.0-0.5;
88 if(cy==0.0 && imageSize.height > 0)
90 cy = double(imageSize.height)/2.0-0.5;
95 P_ = cv::Mat::eye(3, 4, CV_64FC1),
96 P_.at<
double>(0,0) = fx;
97 P_.at<
double>(1,1) = fy;
98 P_.at<
double>(0,2) = cx;
99 P_.at<
double>(1,2) = cy;
100 P_.at<
double>(0,3) = Tx;
103 K_.at<
double>(0,0) = fx;
104 K_.at<
double>(1,1) = fy;
105 K_.at<
double>(0,2) = cx;
106 K_.at<
double>(1,2) = cy;
110 const std::string &
name,
120 K_(
cv::Mat::eye(3, 3, CV_64FC1)),
125 UASSERT_MSG(cx >= 0.0 && imageSize.width>=0,
uFormat(
"cx=%f imageSize.width=%d", cx, imageSize.width).c_str());
126 UASSERT_MSG(cy >= 0.0 && imageSize.height>=0,
uFormat(
"cy=%f imageSize.height=%d", cy, imageSize.height).c_str());
129 if(cx==0.0 && imageSize.width > 0)
131 cx = double(imageSize.width)/2.0-0.5;
133 if(cy==0.0 && imageSize.height > 0)
135 cy = double(imageSize.height)/2.0-0.5;
140 P_ = cv::Mat::eye(3, 4, CV_64FC1),
141 P_.at<
double>(0,0) = fx;
142 P_.at<
double>(1,1) = fy;
143 P_.at<
double>(0,2) = cx;
144 P_.at<
double>(1,2) = cy;
145 P_.at<
double>(0,3) = Tx;
148 K_.at<
double>(0,0) = fx;
149 K_.at<
double>(1,1) = fy;
150 K_.at<
double>(0,2) = cx;
151 K_.at<
double>(1,2) = cy;
157 UASSERT(
D_.rows == 1 && (
D_.cols == 4 ||
D_.cols == 5 ||
D_.cols == 6 ||
D_.cols == 8));
161 UINFO(
"Initialize rectify map");
164 #if CV_MAJOR_VERSION > 2 or (CV_MAJOR_VERSION == 2 and (CV_MINOR_VERSION >4 or (CV_MINOR_VERSION == 4 and CV_SUBMINOR_VERSION >=10))) 167 cv::Mat
D(1, 4, CV_64FC1);
168 D.at<
double>(0,0) =
D_.at<
double>(0,1);
169 D.at<
double>(0,1) =
D_.at<
double>(0,2);
170 D.at<
double>(0,2) =
D_.at<
double>(0,4);
171 D.at<
double>(0,3) =
D_.at<
double>(0,5);
176 UWARN(
"Too old opencv version (%d,%d,%d) to support fisheye model (min 2.4.10 required)!",
177 CV_MAJOR_VERSION, CV_MINOR_VERSION, CV_SUBMINOR_VERSION);
188 UASSERT((size.height > 0 && size.width > 0) || (size.height == 0 && size.width == 0));
202 P_.at<
double>(0,2) = ncx;
203 P_.at<
double>(1,2) = ncy;
207 K_.at<
double>(0,2) = ncx;
208 K_.at<
double>(1,2) = ncy;
223 std::string filePath = directory+
"/"+cameraName+
".yaml";
228 UINFO(
"Reading calibration file \"%s\"", filePath.c_str());
229 cv::FileStorage fs(filePath, cv::FileStorage::READ);
233 n = fs[
"camera_name"];
234 if(n.type() != cv::FileNode::NONE)
240 UWARN(
"Missing \"camera_name\" field in \"%s\"", filePath.c_str());
243 n = fs[
"image_width"];
244 n2 = fs[
"image_height"];
245 if(n.type() != cv::FileNode::NONE)
252 UWARN(
"Missing \"image_width\" and/or \"image_height\" fields in \"%s\"", filePath.c_str());
256 n = fs[
"camera_matrix"];
257 if(n.type() != cv::FileNode::NONE)
259 int rows = (int)n[
"rows"];
260 int cols = (int)n[
"cols"];
261 std::vector<double> data;
263 UASSERT(rows*cols == (
int)data.size());
264 UASSERT(rows == 3 && cols == 3);
265 K_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
269 UWARN(
"Missing \"camera_matrix\" field in \"%s\"", filePath.c_str());
272 n = fs[
"distortion_coefficients"];
273 if(n.type() != cv::FileNode::NONE)
275 int rows = (int)n[
"rows"];
276 int cols = (int)n[
"cols"];
277 std::vector<double> data;
279 UASSERT(rows*cols == (
int)data.size());
280 UASSERT(rows == 1 && (cols == 4 || cols == 5 || cols == 8));
281 D_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
285 UWARN(
"Missing \"distorsion_coefficients\" field in \"%s\"", filePath.c_str());
288 n = fs[
"distortion_model"];
289 if(n.type() != cv::FileNode::NONE)
291 std::string distortionModel = (std::string)n;
296 cv::Mat
D = cv::Mat::zeros(1,6,CV_64FC1);
297 D.at<
double>(0,0) =
D_.at<
double>(0,0);
298 D.at<
double>(0,1) =
D_.at<
double>(0,1);
299 D.at<
double>(0,4) =
D_.at<
double>(0,2);
300 D.at<
double>(0,5) =
D_.at<
double>(0,3);
306 UWARN(
"Missing \"distortion_model\" field in \"%s\"", filePath.c_str());
309 n = fs[
"rectification_matrix"];
310 if(n.type() != cv::FileNode::NONE)
312 int rows = (int)n[
"rows"];
313 int cols = (int)n[
"cols"];
314 std::vector<double> data;
316 UASSERT(rows*cols == (
int)data.size());
317 UASSERT(rows == 3 && cols == 3);
318 R_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
322 UWARN(
"Missing \"rectification_matrix\" field in \"%s\"", filePath.c_str());
325 n = fs[
"projection_matrix"];
326 if(n.type() != cv::FileNode::NONE)
328 int rows = (int)n[
"rows"];
329 int cols = (int)n[
"cols"];
330 std::vector<double> data;
332 UASSERT(rows*cols == (
int)data.size());
333 UASSERT(rows == 3 && cols == 4);
334 P_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
338 UWARN(
"Missing \"projection_matrix\" field in \"%s\"", filePath.c_str());
350 catch(
const cv::Exception &
e)
352 UERROR(
"Error reading calibration file \"%s\": %s", filePath.c_str(), e.what());
357 UWARN(
"Could not load calibration file \"%s\".", filePath.c_str());
364 std::string filePath = directory+
"/"+
name_+
".yaml";
365 if(!filePath.empty() && (!
K_.empty() || !
D_.empty() || !
R_.empty() || !
P_.empty()))
367 UINFO(
"Saving calibration to file \"%s\"", filePath.c_str());
368 cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
374 fs <<
"camera_name" <<
name_;
384 fs <<
"camera_matrix" <<
"{";
385 fs <<
"rows" <<
K_.rows;
386 fs <<
"cols" <<
K_.cols;
387 fs <<
"data" << std::vector<double>((
double*)
K_.data, ((
double*)
K_.data)+(
K_.rows*
K_.cols));
396 D = cv::Mat(1,4,CV_64FC1);
397 D.at<
double>(0,0) =
D_.at<
double>(0,0);
398 D.at<
double>(0,1) =
D_.at<
double>(0,1);
399 D.at<
double>(0,2) =
D_.at<
double>(0,4);
400 D.at<
double>(0,3) =
D_.at<
double>(0,5);
402 fs <<
"distortion_coefficients" <<
"{";
403 fs <<
"rows" << D.rows;
404 fs <<
"cols" << D.cols;
405 fs <<
"data" << std::vector<double>((
double*)D.data, ((
double*)D.data)+(D.rows*D.cols));
411 fs <<
"distortion_model" <<
"equidistant";
415 fs <<
"distortion_model" <<
"rational_polynomial";
419 fs <<
"distortion_model" <<
"plumb_bob";
425 fs <<
"rectification_matrix" <<
"{";
426 fs <<
"rows" <<
R_.rows;
427 fs <<
"cols" <<
R_.cols;
428 fs <<
"data" << std::vector<double>((
double*)
R_.data, ((
double*)
R_.data)+(
R_.rows*
R_.cols));
434 fs <<
"projection_matrix" <<
"{";
435 fs <<
"rows" <<
P_.rows;
436 fs <<
"cols" <<
P_.cols;
437 fs <<
"data" << std::vector<double>((
double*)
P_.data, ((
double*)
P_.data)+(
P_.rows*
P_.cols));
447 UERROR(
"Cannot save calibration to \"%s\" because it is empty.", filePath.c_str());
463 K.at<
double>(0,0) *= scale;
464 K.at<
double>(1,1) *= scale;
465 K.at<
double>(0,2) *= scale;
466 K.at<
double>(1,2) *= scale;
473 P.at<
double>(0,0) *= scale;
474 P.at<
double>(1,1) *= scale;
475 P.at<
double>(0,2) *= scale;
476 P.at<
double>(1,2) *= scale;
477 P.at<
double>(0,3) *= scale;
478 P.at<
double>(1,3) *= scale;
484 UWARN(
"Trying to scale a camera model not valid! Ignoring scaling...");
499 K.at<
double>(0,2) -= roi.x;
500 K.at<
double>(1,2) -= roi.y;
507 P.at<
double>(0,2) -= roi.x;
508 P.at<
double>(1,2) -= roi.y;
514 UWARN(
"Trying to extract roi from a camera model not valid! Ignoring roi...");
543 cv::remap(raw, rectified,
mapX_,
mapY_, interpolation);
548 UERROR(
"Cannot rectify image because the rectify map is not initialized.");
557 UASSERT(raw.type() == CV_16UC1);
560 cv::Mat rectified = cv::Mat::zeros(
mapX_.rows,
mapX_.cols, raw.type());
561 for(
int y=0; y<
mapX_.rows; ++y)
563 for(
int x=0; x<
mapX_.cols; ++x)
565 cv::Point2f pt(
mapX_.at<
float>(y,x),
mapY_.at<
float>(y,x));
566 int xL = (int)
floor(pt.x);
567 int xH = (int)
ceil(pt.x);
568 int yL = (int)
floor(pt.y);
569 int yH = (int)
ceil(pt.y);
570 if(xL >= 0 && yL >= 0 && xH < raw.cols && yH < raw.rows)
572 const unsigned short & pLT = raw.at<
unsigned short>(yL, xL);
573 const unsigned short & pRT = raw.at<
unsigned short>(yL, xH);
574 const unsigned short & pLB = raw.at<
unsigned short>(yH, xL);
575 const unsigned short & pRB = raw.at<
unsigned short>(yH, xH);
576 if(pLT > 0 && pRT > 0 && pLB > 0 && pRB > 0)
578 unsigned short avg = (pLT + pRT + pLB + pRB) / 4;
579 unsigned short thres = 0.01 * avg;
580 if(
abs(pLT - avg) < thres &&
581 abs(pRT - avg) < thres &&
582 abs(pLB - avg) < thres &&
583 abs(pRB - avg) < thres)
586 float a = pt.x - (float)xL;
587 float c = pt.y - (float)yL;
590 rectified.at<
unsigned short>(y,x) =
591 (pLT * (1.
f - a) + pRT * a) * (1.
f - c) +
592 (pLB * (1.f - a) + pRB * a) * c;
602 UERROR(
"Cannot rectify image because the rectify map is not initialized.");
613 x = (u -
cx()) * depth /
fx();
614 y = (v -
cy()) * depth /
fy();
619 x = y = z = std::numeric_limits<float>::quiet_NaN();
627 u = (
fx()*x)*invZ +
cx();
628 v = (
fy()*y)*invZ +
cy();
634 u = (
fx()*x)*invZ +
cx();
635 v = (
fy()*y)*invZ +
cy();
void setImageSize(const cv::Size &size)
const cv::Size & imageSize() const
const std::string & name() const
bool uIsInBounds(const T &value, const T &low, const T &high)
bool inFrame(int u, int v) const
Transform localTransform_
bool save(const std::string &directory) const
GLM_FUNC_DECL genType e()
double verticalFOV() const
Basic mathematics functions.
Some conversion functions.
bool uStrContains(const std::string &string, const std::string &substring)
#define UASSERT(condition)
double horizontalFOV() const
Wrappers of STL for convenient functions.
bool load(const std::string &directory, const std::string &cameraName)
void initRectificationMap()
GLM_FUNC_DECL genType floor(genType const &x)
#define UASSERT_MSG(condition, msg_str)
void reproject(float x, float y, float z, float &u, float &v) const
GLM_FUNC_DECL genType atan(genType const &y, genType const &x)
GLM_FUNC_DECL genType abs(genType const &x)
bool isValidForRectification() const
CameraModel roi(const cv::Rect &roi) const
void project(float u, float v, float depth, float &x, float &y, float &z) const
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
bool isValidForProjection() const
cv::Mat rectifyDepth(const cv::Mat &raw) const
ULogger class and convenient macros.
std::string UTILITE_EXP uFormat(const char *fmt,...)
GLM_FUNC_DECL genType ceil(genType const &x)
CameraModel scaled(double scale) const
const Transform & localTransform() const