29 #include <rtabmap/core/Version.h> 36 #include <opencv2/imgproc/imgproc.hpp> 41 localTransform_(opticalRotation())
47 const std::string & cameraName,
62 UASSERT(
K_.empty() || (
K_.rows == 3 &&
K_.cols == 3 &&
K_.type() == CV_64FC1));
63 UASSERT(
D_.empty() || (
D_.rows == 1 && (
D_.cols == 4 ||
D_.cols == 5 ||
D_.cols == 6 ||
D_.cols == 8) &&
D_.type() == CV_64FC1));
64 UASSERT(
R_.empty() || (
R_.rows == 3 &&
R_.cols == 3 &&
R_.type() == CV_64FC1));
65 UASSERT(
P_.empty() || (
P_.rows == 3 &&
P_.cols == 4 &&
P_.type() == CV_64FC1));
77 K_(
cv::Mat::eye(3, 3, CV_64FC1)),
82 UASSERT_MSG(cx >= 0.0 && imageSize.width>=0,
uFormat(
"cx=%f imageSize.width=%d", cx, imageSize.width).c_str());
83 UASSERT_MSG(cy >= 0.0 && imageSize.height>=0,
uFormat(
"cy=%f imageSize.height=%d", cy, imageSize.height).c_str());
86 if(cx==0.0 && imageSize.width > 0)
88 cx = double(imageSize.width)/2.0-0.5;
90 if(cy==0.0 && imageSize.height > 0)
92 cy = double(imageSize.height)/2.0-0.5;
97 P_ = cv::Mat::eye(3, 4, CV_64FC1),
98 P_.at<
double>(0,0) = fx;
99 P_.at<
double>(1,1) = fy;
100 P_.at<
double>(0,2) = cx;
101 P_.at<
double>(1,2) = cy;
102 P_.at<
double>(0,3) = Tx;
105 K_.at<
double>(0,0) = fx;
106 K_.at<
double>(1,1) = fy;
107 K_.at<
double>(0,2) = cx;
108 K_.at<
double>(1,2) = cy;
112 const std::string &
name,
122 K_(
cv::Mat::eye(3, 3, CV_64FC1)),
127 UASSERT_MSG(cx >= 0.0 && imageSize.width>=0,
uFormat(
"cx=%f imageSize.width=%d", cx, imageSize.width).c_str());
128 UASSERT_MSG(cy >= 0.0 && imageSize.height>=0,
uFormat(
"cy=%f imageSize.height=%d", cy, imageSize.height).c_str());
131 if(cx==0.0 && imageSize.width > 0)
133 cx = double(imageSize.width)/2.0-0.5;
135 if(cy==0.0 && imageSize.height > 0)
137 cy = double(imageSize.height)/2.0-0.5;
142 P_ = cv::Mat::eye(3, 4, CV_64FC1),
143 P_.at<
double>(0,0) = fx;
144 P_.at<
double>(1,1) = fy;
145 P_.at<
double>(0,2) = cx;
146 P_.at<
double>(1,2) = cy;
147 P_.at<
double>(0,3) = Tx;
150 K_.at<
double>(0,0) = fx;
151 K_.at<
double>(1,1) = fy;
152 K_.at<
double>(0,2) = cx;
153 K_.at<
double>(1,2) = cy;
159 UASSERT(
D_.rows == 1 && (
D_.cols == 4 ||
D_.cols == 5 ||
D_.cols == 6 ||
D_.cols == 8));
163 UINFO(
"Initialize rectify map");
166 #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))) 169 cv::Mat
D(1, 4, CV_64FC1);
170 D.at<
double>(0,0) =
D_.at<
double>(0,0);
171 D.at<
double>(0,1) =
D_.at<
double>(0,1);
172 D.at<
double>(0,2) =
D_.at<
double>(0,4);
173 D.at<
double>(0,3) =
D_.at<
double>(0,5);
178 UWARN(
"Too old opencv version (%d,%d,%d) to support fisheye model (min 2.4.10 required)!",
179 CV_MAJOR_VERSION, CV_MINOR_VERSION, CV_SUBMINOR_VERSION);
191 UASSERT((size.height > 0 && size.width > 0) || (size.height == 0 && size.width == 0));
205 P_.at<
double>(0,2) = ncx;
206 P_.at<
double>(1,2) = ncy;
210 K_.at<
double>(0,2) = ncx;
211 K_.at<
double>(1,2) = ncy;
230 UINFO(
"Reading calibration file \"%s\"", filePath.c_str());
231 cv::FileStorage fs(filePath, cv::FileStorage::READ);
235 n = fs[
"camera_name"];
236 if(n.type() != cv::FileNode::NONE)
238 name_ = (std::string)n;
242 UWARN(
"Missing \"camera_name\" field in \"%s\"", filePath.c_str());
245 n = fs[
"image_width"];
246 n2 = fs[
"image_height"];
247 if(n.type() != cv::FileNode::NONE)
254 UWARN(
"Missing \"image_width\" and/or \"image_height\" fields in \"%s\"", filePath.c_str());
258 n = fs[
"camera_matrix"];
259 if(n.type() != cv::FileNode::NONE)
261 int rows = (int)n[
"rows"];
262 int cols = (int)n[
"cols"];
263 std::vector<double>
data;
265 UASSERT(rows*cols == (
int)data.size());
266 UASSERT(rows == 3 && cols == 3);
267 K_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
271 UWARN(
"Missing \"camera_matrix\" field in \"%s\"", filePath.c_str());
274 n = fs[
"distortion_coefficients"];
275 if(n.type() != cv::FileNode::NONE)
277 int rows = (int)n[
"rows"];
278 int cols = (int)n[
"cols"];
279 std::vector<double>
data;
281 UASSERT(rows*cols == (
int)data.size());
282 UASSERT(rows == 1 && (cols == 4 || cols == 5 || cols == 8));
283 D_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
287 UWARN(
"Missing \"distorsion_coefficients\" field in \"%s\"", filePath.c_str());
290 n = fs[
"distortion_model"];
291 if(n.type() != cv::FileNode::NONE)
293 std::string distortionModel = (std::string)n;
298 cv::Mat
D = cv::Mat::zeros(1,6,CV_64FC1);
299 D.at<
double>(0,0) =
D_.at<
double>(0,0);
300 D.at<
double>(0,1) =
D_.at<
double>(0,1);
301 D.at<
double>(0,4) =
D_.at<
double>(0,2);
302 D.at<
double>(0,5) =
D_.at<
double>(0,3);
308 UWARN(
"Missing \"distortion_model\" field in \"%s\"", filePath.c_str());
311 n = fs[
"rectification_matrix"];
312 if(n.type() != cv::FileNode::NONE)
314 int rows = (int)n[
"rows"];
315 int cols = (int)n[
"cols"];
316 std::vector<double>
data;
318 UASSERT(rows*cols == (
int)data.size());
319 UASSERT(rows == 3 && cols == 3);
320 R_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
324 UWARN(
"Missing \"rectification_matrix\" field in \"%s\"", filePath.c_str());
327 n = fs[
"projection_matrix"];
328 if(n.type() != cv::FileNode::NONE)
330 int rows = (int)n[
"rows"];
331 int cols = (int)n[
"cols"];
332 std::vector<double>
data;
334 UASSERT(rows*cols == (
int)data.size());
335 UASSERT(rows == 3 && cols == 4);
336 P_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
340 UWARN(
"Missing \"projection_matrix\" field in \"%s\"", filePath.c_str());
343 n = fs[
"local_transform"];
344 if(n.type() != cv::FileNode::NONE)
346 int rows = (int)n[
"rows"];
347 int cols = (int)n[
"cols"];
348 std::vector<float>
data;
350 UASSERT(rows*cols == (
int)data.size());
351 UASSERT(rows == 3 && cols == 4);
353 data[0], data[1], data[2], data[3],
354 data[4], data[5], data[6], data[7],
355 data[8], data[9], data[10], data[11]);
359 UWARN(
"Missing \"local_transform\" field in \"%s\"", filePath.c_str());
371 catch(
const cv::Exception &
e)
373 UERROR(
"Error reading calibration file \"%s\": %s (Make sure the first line of the yaml file is \"%YAML:1.0\")", filePath.c_str(), e.what());
378 UWARN(
"Could not load calibration file \"%s\".", filePath.c_str());
385 return load(directory+
"/"+cameraName+
".yaml");
392 UWARN(
"Camera name is empty, will use general \"camera\" as name.");
394 std::string filePath = directory+
"/"+(
name_.empty()?
"camera":
name_)+
".yaml";
395 if(!filePath.empty() && (!
K_.empty() || !
D_.empty() || !
R_.empty() || !
P_.empty()))
397 UINFO(
"Saving calibration to file \"%s\"", filePath.c_str());
398 cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
404 fs <<
"camera_name" <<
name_;
414 fs <<
"camera_matrix" <<
"{";
415 fs <<
"rows" <<
K_.rows;
416 fs <<
"cols" <<
K_.cols;
417 fs <<
"data" << std::vector<double>((
double*)
K_.data, ((
double*)
K_.data)+(
K_.rows*
K_.cols));
426 D = cv::Mat(1,4,CV_64FC1);
427 D.at<
double>(0,0) =
D_.at<
double>(0,0);
428 D.at<
double>(0,1) =
D_.at<
double>(0,1);
429 D.at<
double>(0,2) =
D_.at<
double>(0,4);
430 D.at<
double>(0,3) =
D_.at<
double>(0,5);
432 fs <<
"distortion_coefficients" <<
"{";
433 fs <<
"rows" << D.rows;
434 fs <<
"cols" << D.cols;
435 fs <<
"data" << std::vector<double>((
double*)D.data, ((
double*)D.data)+(D.rows*D.cols));
441 fs <<
"distortion_model" <<
"equidistant";
445 fs <<
"distortion_model" <<
"rational_polynomial";
449 fs <<
"distortion_model" <<
"plumb_bob";
455 fs <<
"rectification_matrix" <<
"{";
456 fs <<
"rows" <<
R_.rows;
457 fs <<
"cols" <<
R_.cols;
458 fs <<
"data" << std::vector<double>((
double*)
R_.data, ((
double*)
R_.data)+(
R_.rows*
R_.cols));
464 fs <<
"projection_matrix" <<
"{";
465 fs <<
"rows" <<
P_.rows;
466 fs <<
"cols" <<
P_.cols;
467 fs <<
"data" << std::vector<double>((
double*)
P_.data, ((
double*)
P_.data)+(
P_.rows*
P_.cols));
473 fs <<
"local_transform" <<
"{";
486 UERROR(
"Cannot save calibration to \"%s\" because it is empty.", filePath.c_str());
493 const int headerSize = 11;
494 int header[headerSize] = {
495 RTABMAP_VERSION_MAJOR, RTABMAP_VERSION_MINOR, RTABMAP_VERSION_PATCH,
498 (int)
K_.total(), (int)
D_.total(), (int)
R_.total(), (int)
P_.total(),
500 UDEBUG(
"Header: %d %d %d %d %d %d %d %d %d %d %d", header[0],header[1],header[2],header[3],header[4],header[5],header[6],header[7],header[8],header[9],header[10]);
501 std::vector<unsigned char>
data(
502 sizeof(
int)*headerSize +
503 sizeof(
double)*(
K_.total()+
D_.total()+
R_.total()+
P_.total()) +
505 memcpy(data.data(), header,
sizeof(int)*headerSize);
506 int index =
sizeof(int)*headerSize;
509 memcpy(data.data()+index,
K_.data,
sizeof(double)*(
K_.total()));
510 index+=
sizeof(double)*(
K_.total());
514 memcpy(data.data()+index,
D_.data,
sizeof(double)*(
D_.total()));
515 index+=
sizeof(double)*(
D_.total());
519 memcpy(data.data()+index,
R_.data,
sizeof(double)*(
R_.total()));
520 index+=
sizeof(double)*(
R_.total());
524 memcpy(data.data()+index,
P_.data,
sizeof(double)*(
P_.total()));
525 index+=
sizeof(double)*(
P_.total());
543 if(dataSize >=
sizeof(
int)*headerSize)
546 const int *
header = (
const int *)data;
547 int type = header[3];
557 UDEBUG(
"Header: %d %d %d %d %d %d %d %d %d %d %d", header[0],header[1],header[2],header[3],header[4],header[5],header[6],header[7],header[8],header[9],header[10]);
558 unsigned int requiredDataSize =
sizeof(int)*headerSize +
559 sizeof(
double)*(header[iK]+header[iD]+header[iR]+header[iP]) +
560 sizeof(
float)*header[iL];
562 uFormat(
"dataSize=%d != required=%d (header: version %d.%d.%d %dx%d type=%d K=%d D=%d R=%d P=%d L=%d)",
565 header[0], header[1], header[2], header[4], header[5], header[3],
566 header[iK], header[iD], header[iR],header[iP], header[iL]).c_str());
567 unsigned int index =
sizeof(int)*headerSize;
571 K_ = cv::Mat(3, 3, CV_64FC1, (
void*)(data+index)).clone();
572 index+=
sizeof(double)*(
K_.total());
576 D_ = cv::Mat(1, header[iD], CV_64FC1, (
void*)(data+index)).clone();
577 index+=
sizeof(double)*(
D_.total());
582 R_ = cv::Mat(3, 3, CV_64FC1, (
void*)(data+index)).clone();
583 index+=
sizeof(double)*(
R_.total());
588 P_ = cv::Mat(3, 4, CV_64FC1, (
void*)(data+index)).clone();
589 index+=
sizeof(double)*(
P_.total());
602 UERROR(
"Serialized calibration is not mono (type=%d), use the appropriate class matching the type to deserialize.", type);
605 UERROR(
"Wrong serialized calibration data format detected (size in bytes=%d)! Cannot deserialize the data.", (
int)dataSize);
620 K.at<
double>(0,0) *= scale;
621 K.at<
double>(1,1) *= scale;
622 K.at<
double>(0,2) *= scale;
623 K.at<
double>(1,2) *= scale;
630 P.at<
double>(0,0) *= scale;
631 P.at<
double>(1,1) *= scale;
632 P.at<
double>(0,2) *= scale;
633 P.at<
double>(1,2) *= scale;
634 P.at<
double>(0,3) *= scale;
635 P.at<
double>(1,3) *= scale;
641 UWARN(
"Trying to scale a camera model not valid! Ignoring scaling...");
656 K.at<
double>(0,2) -= roi.x;
657 K.at<
double>(1,2) -= roi.y;
664 P.at<
double>(0,2) -= roi.x;
665 P.at<
double>(1,2) -= roi.y;
671 UWARN(
"Trying to extract roi from a camera model not valid! Ignoring roi...");
687 return fovX()*180.0/CV_PI;
692 return fovY()*180.0/CV_PI;
701 cv::remap(raw, rectified,
mapX_,
mapY_, interpolation);
706 UERROR(
"Cannot rectify image because the rectify map is not initialized.");
715 UASSERT(raw.type() == CV_16UC1);
718 cv::Mat rectified = cv::Mat::zeros(
mapX_.rows,
mapX_.cols, raw.type());
719 for(
int y=0; y<
mapX_.rows; ++y)
723 cv::Point2f pt(
mapX_.at<
float>(y,
x),
mapY_.at<
float>(y,
x));
724 int xL = (int)
floor(pt.x);
725 int xH = (int)
ceil(pt.x);
726 int yL = (int)
floor(pt.y);
727 int yH = (int)
ceil(pt.y);
728 if(xL >= 0 && yL >= 0 && xH < raw.cols && yH < raw.rows)
730 const unsigned short & pLT = raw.at<
unsigned short>(yL, xL);
731 const unsigned short & pRT = raw.at<
unsigned short>(yL, xH);
732 const unsigned short & pLB = raw.at<
unsigned short>(yH, xL);
733 const unsigned short & pRB = raw.at<
unsigned short>(yH, xH);
734 if(pLT > 0 && pRT > 0 && pLB > 0 && pRB > 0)
736 unsigned short avg = (pLT + pRT + pLB + pRB) / 4;
737 unsigned short thres = 0.01 * avg;
738 if(
abs(pLT - avg) < thres &&
739 abs(pRT - avg) < thres &&
740 abs(pLB - avg) < thres &&
741 abs(pRB - avg) < thres)
744 float a = pt.x - (float)xL;
745 float c = pt.y - (float)yL;
748 rectified.at<
unsigned short>(y,
x) =
749 (pLT * (1.
f - a) + pRT * a) * (1.
f - c) +
750 (pLB * (1.f - a) + pRB * a) * c;
760 UERROR(
"Cannot rectify image because the rectify map is not initialized.");
771 x = (u -
cx()) * depth /
fx();
772 y = (v -
cy()) * depth /
fy();
777 x = y = z = std::numeric_limits<float>::quiet_NaN();
785 u = (
fx()*x)*invZ +
cx();
786 v = (
fy()*y)*invZ +
cy();
792 u = (
fx()*x)*invZ +
cx();
793 v = (
fy()*y)*invZ +
cy();
803 os <<
"Name: " << model.
name().c_str() << std::endl
805 <<
"K= " << model.
K_raw() << std::endl
806 <<
"D= " << model.
D_raw() << std::endl
807 <<
"R= " << model.
R() << std::endl
808 <<
"P= " << model.
P() << std::endl
const cv::Size & imageSize() const
std::vector< unsigned char > serialize() const
void setImageSize(const cv::Size &size)
double horizontalFOV() const
CameraModel scaled(double scale) const
bool isRectificationMapInitialized() const
bool save(const std::string &directory) const
bool uIsInBounds(const T &value, const T &low, const T &high)
double verticalFOV() const
Transform localTransform_
GLM_FUNC_DECL genType e()
Basic mathematics functions.
bool load(const std::string &filePath)
std_msgs::Header * header(M &m)
Some conversion functions.
void reproject(float x, float y, float z, float &u, float &v) const
bool uStrContains(const std::string &string, const std::string &substring)
bool initRectificationMap()
#define UASSERT(condition)
Wrappers of STL for convenient functions.
GLM_FUNC_DECL genType floor(genType const &x)
bool isValidForRectification() const
#define UASSERT_MSG(condition, msg_str)
GLM_FUNC_DECL genType atan(genType const &y, genType const &x)
GLM_FUNC_DECL genType abs(genType const &x)
CameraModel roi(const cv::Rect &roi) const
const Transform & localTransform() const
cv::Mat rectifyDepth(const cv::Mat &raw) const
cv::Mat rectifyImage(const cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
RTABMAP_EXP std::ostream & operator<<(std::ostream &os, const CameraModel &model)
ULogger class and convenient macros.
const std::string & name() const
unsigned int deserialize(const std::vector< unsigned char > &data)
bool inFrame(int u, int v) const
std::string UTILITE_EXP uFormat(const char *fmt,...)
GLM_FUNC_DECL genType ceil(genType const &x)
bool isValidForProjection() const
void project(float u, float v, float depth, float &x, float &y, float &z) const