CameraModel.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
31 #include <rtabmap/utilite/UFile.h>
33 #include <rtabmap/utilite/UMath.h>
34 #include <rtabmap/utilite/UStl.h>
35 #include <opencv2/imgproc/imgproc.hpp>
36 
37 namespace rtabmap {
38 
40 {
41 
42 }
43 
45  const std::string & cameraName,
46  const cv::Size & imageSize,
47  const cv::Mat & K,
48  const cv::Mat & D,
49  const cv::Mat & R,
50  const cv::Mat & P,
51  const Transform & localTransform) :
52  name_(cameraName),
53  imageSize_(imageSize),
54  K_(K),
55  D_(D),
56  R_(R),
57  P_(P),
58  localTransform_(localTransform)
59 {
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));
64 }
65 
67  double fx,
68  double fy,
69  double cx,
70  double cy,
71  const Transform & localTransform,
72  double Tx,
73  const cv::Size & imageSize) :
74  imageSize_(imageSize),
75  K_(cv::Mat::eye(3, 3, CV_64FC1)),
76  localTransform_(localTransform)
77 {
78  UASSERT_MSG(fx > 0.0, uFormat("fx=%f", fx).c_str());
79  UASSERT_MSG(fy > 0.0, uFormat("fy=%f", fy).c_str());
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());
82  UASSERT(!localTransform.isNull());
83 
84  if(cx==0.0 && imageSize.width > 0)
85  {
86  cx = double(imageSize.width)/2.0-0.5;
87  }
88  if(cy==0.0 && imageSize.height > 0)
89  {
90  cy = double(imageSize.height)/2.0-0.5;
91  }
92 
93  if(Tx != 0.0)
94  {
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;
101  }
102 
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;
107 }
108 
110  const std::string & name,
111  double fx,
112  double fy,
113  double cx,
114  double cy,
115  const Transform & localTransform,
116  double Tx,
117  const cv::Size & imageSize) :
118  name_(name),
119  imageSize_(imageSize),
120  K_(cv::Mat::eye(3, 3, CV_64FC1)),
121  localTransform_(localTransform)
122 {
123  UASSERT_MSG(fx > 0.0, uFormat("fx=%f", fx).c_str());
124  UASSERT_MSG(fy > 0.0, uFormat("fy=%f", fy).c_str());
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());
127  UASSERT(!localTransform.isNull());
128 
129  if(cx==0.0 && imageSize.width > 0)
130  {
131  cx = double(imageSize.width)/2.0-0.5;
132  }
133  if(cy==0.0 && imageSize.height > 0)
134  {
135  cy = double(imageSize.height)/2.0-0.5;
136  }
137 
138  if(Tx != 0.0)
139  {
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;
146  }
147 
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;
152 }
153 
155 {
156  UASSERT(imageSize_.height > 0 && imageSize_.width > 0);
157  UASSERT(D_.rows == 1 && (D_.cols == 4 || D_.cols == 5 || D_.cols == 6 || D_.cols == 8));
158  UASSERT(R_.rows == 3 && R_.cols == 3);
159  UASSERT(P_.rows == 3 && P_.cols == 4);
160  // init rectification map
161  UINFO("Initialize rectify map");
162  if(D_.cols == 6)
163  {
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)))
165  // Equidistant / FishEye
166  // get only k parameters (k1,k2,p1,p2,k3,k4)
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);
172  cv::fisheye::initUndistortRectifyMap(K_, D, R_, P_, imageSize_, CV_32FC1, mapX_, mapY_);
173  }
174  else
175 #else
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);
178  }
179 #endif
180  {
181  // RadialTangential
182  cv::initUndistortRectifyMap(K_, D_, R_, P_, imageSize_, CV_32FC1, mapX_, mapY_);
183  }
184 }
185 
186 void CameraModel::setImageSize(const cv::Size & size)
187 {
188  UASSERT((size.height > 0 && size.width > 0) || (size.height == 0 && size.width == 0));
189  imageSize_ = size;
190  double ncx = cx();
191  double ncy = cy();
192  if(ncx==0.0 && imageSize_.width > 0)
193  {
194  ncx = double(imageSize_.width)/2.0-0.5;
195  }
196  if(ncy==0.0 && imageSize_.height > 0)
197  {
198  ncy = double(imageSize_.height)/2.0-0.5;
199  }
200  if(!P_.empty())
201  {
202  P_.at<double>(0,2) = ncx;
203  P_.at<double>(1,2) = ncy;
204  }
205  if(!K_.empty())
206  {
207  K_.at<double>(0,2) = ncx;
208  K_.at<double>(1,2) = ncy;
209  }
210 }
211 
212 bool CameraModel::load(const std::string & directory, const std::string & cameraName)
213 {
214  K_ = cv::Mat();
215  D_ = cv::Mat();
216  R_ = cv::Mat();
217  P_ = cv::Mat();
218  mapX_ = cv::Mat();
219  mapY_ = cv::Mat();
220  name_.clear();
221  imageSize_ = cv::Size();
222 
223  std::string filePath = directory+"/"+cameraName+".yaml";
224  if(UFile::exists(filePath))
225  {
226  try
227  {
228  UINFO("Reading calibration file \"%s\"", filePath.c_str());
229  cv::FileStorage fs(filePath, cv::FileStorage::READ);
230 
231  cv::FileNode n,n2;
232 
233  n = fs["camera_name"];
234  if(n.type() != cv::FileNode::NONE)
235  {
236  name_ = (int)n;
237  }
238  else
239  {
240  UWARN("Missing \"camera_name\" field in \"%s\"", filePath.c_str());
241  }
242 
243  n = fs["image_width"];
244  n2 = fs["image_height"];
245  if(n.type() != cv::FileNode::NONE)
246  {
247  imageSize_.width = (int)fs["image_width"];
248  imageSize_.height = (int)fs["image_height"];
249  }
250  else
251  {
252  UWARN("Missing \"image_width\" and/or \"image_height\" fields in \"%s\"", filePath.c_str());
253  }
254 
255  // import from ROS calibration format
256  n = fs["camera_matrix"];
257  if(n.type() != cv::FileNode::NONE)
258  {
259  int rows = (int)n["rows"];
260  int cols = (int)n["cols"];
261  std::vector<double> data;
262  n["data"] >> 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();
266  }
267  else
268  {
269  UWARN("Missing \"camera_matrix\" field in \"%s\"", filePath.c_str());
270  }
271 
272  n = fs["distortion_coefficients"];
273  if(n.type() != cv::FileNode::NONE)
274  {
275  int rows = (int)n["rows"];
276  int cols = (int)n["cols"];
277  std::vector<double> data;
278  n["data"] >> 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();
282  }
283  else
284  {
285  UWARN("Missing \"distorsion_coefficients\" field in \"%s\"", filePath.c_str());
286  }
287 
288  n = fs["distortion_model"];
289  if(n.type() != cv::FileNode::NONE)
290  {
291  std::string distortionModel = (std::string)n;
292  if(D_.cols>=4 &&
293  (uStrContains(distortionModel, "fisheye") ||
294  uStrContains(distortionModel, "equidistant")))
295  {
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);
301  D_ = D;
302  }
303  }
304  else
305  {
306  UWARN("Missing \"distortion_model\" field in \"%s\"", filePath.c_str());
307  }
308 
309  n = fs["rectification_matrix"];
310  if(n.type() != cv::FileNode::NONE)
311  {
312  int rows = (int)n["rows"];
313  int cols = (int)n["cols"];
314  std::vector<double> data;
315  n["data"] >> 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();
319  }
320  else
321  {
322  UWARN("Missing \"rectification_matrix\" field in \"%s\"", filePath.c_str());
323  }
324 
325  n = fs["projection_matrix"];
326  if(n.type() != cv::FileNode::NONE)
327  {
328  int rows = (int)n["rows"];
329  int cols = (int)n["cols"];
330  std::vector<double> data;
331  n["data"] >> 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();
335  }
336  else
337  {
338  UWARN("Missing \"projection_matrix\" field in \"%s\"", filePath.c_str());
339  }
340 
341  fs.release();
342 
344  {
346  }
347 
348  return true;
349  }
350  catch(const cv::Exception & e)
351  {
352  UERROR("Error reading calibration file \"%s\": %s", filePath.c_str(), e.what());
353  }
354  }
355  else
356  {
357  UWARN("Could not load calibration file \"%s\".", filePath.c_str());
358  }
359  return false;
360 }
361 
362 bool CameraModel::save(const std::string & directory) const
363 {
364  std::string filePath = directory+"/"+name_+".yaml";
365  if(!filePath.empty() && (!K_.empty() || !D_.empty() || !R_.empty() || !P_.empty()))
366  {
367  UINFO("Saving calibration to file \"%s\"", filePath.c_str());
368  cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
369 
370  // export in ROS calibration format
371 
372  if(!name_.empty())
373  {
374  fs << "camera_name" << name_;
375  }
376  if(imageSize_.width>0 && imageSize_.height>0)
377  {
378  fs << "image_width" << imageSize_.width;
379  fs << "image_height" << imageSize_.height;
380  }
381 
382  if(!K_.empty())
383  {
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));
388  fs << "}";
389  }
390 
391  if(!D_.empty())
392  {
393  cv::Mat D = D_;
394  if(D_.cols == 6)
395  {
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);
401  }
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));
406  fs << "}";
407 
408  // compaibility with ROS
409  if(D_.cols == 6)
410  {
411  fs << "distortion_model" << "equidistant"; // equidistant, fisheye
412  }
413  else if(D.cols > 5)
414  {
415  fs << "distortion_model" << "rational_polynomial"; // rad tan
416  }
417  else
418  {
419  fs << "distortion_model" << "plumb_bob"; // rad tan
420  }
421  }
422 
423  if(!R_.empty())
424  {
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));
429  fs << "}";
430  }
431 
432  if(!P_.empty())
433  {
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));
438  fs << "}";
439  }
440 
441  fs.release();
442 
443  return true;
444  }
445  else
446  {
447  UERROR("Cannot save calibration to \"%s\" because it is empty.", filePath.c_str());
448  }
449  return false;
450 }
451 
453 {
454  CameraModel scaledModel = *this;
455  UASSERT(scale > 0.0);
456  if(this->isValidForProjection())
457  {
458  // has only effect on K and P
459  cv::Mat K;
460  if(!K_.empty())
461  {
462  K = K_.clone();
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;
467  }
468 
469  cv::Mat P;
470  if(!P_.empty())
471  {
472  P = P_.clone();
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;
479  }
480  scaledModel = CameraModel(name_, cv::Size(double(imageSize_.width)*scale, double(imageSize_.height)*scale), K, D_, R_, P, localTransform_);
481  }
482  else
483  {
484  UWARN("Trying to scale a camera model not valid! Ignoring scaling...");
485  }
486  return scaledModel;
487 }
488 
489 CameraModel CameraModel::roi(const cv::Rect & roi) const
490 {
491  CameraModel roiModel = *this;
492  if(this->isValidForProjection())
493  {
494  // has only effect on cx and cy
495  cv::Mat K;
496  if(!K_.empty())
497  {
498  K = K_.clone();
499  K.at<double>(0,2) -= roi.x;
500  K.at<double>(1,2) -= roi.y;
501  }
502 
503  cv::Mat P;
504  if(!P_.empty())
505  {
506  P = P_.clone();
507  P.at<double>(0,2) -= roi.x;
508  P.at<double>(1,2) -= roi.y;
509  }
510  roiModel = CameraModel(name_, roi.size(), K, D_, R_, P, localTransform_);
511  }
512  else
513  {
514  UWARN("Trying to extract roi from a camera model not valid! Ignoring roi...");
515  }
516  return roiModel;
517 }
518 
520 {
521  if(imageWidth() > 0 && fx() > 0.0)
522  {
523  return atan((double(imageWidth())/2.0)/fx())*2.0*180.0/CV_PI;
524  }
525  return 0.0;
526 }
527 
529 {
530  if(imageHeight() > 0 && fy() > 0.0)
531  {
532  return atan((double(imageHeight())/2.0)/fy())*2.0*180.0/CV_PI;
533  }
534  return 0.0;
535 }
536 
537 cv::Mat CameraModel::rectifyImage(const cv::Mat & raw, int interpolation) const
538 {
539  UDEBUG("");
540  if(!mapX_.empty() && !mapY_.empty())
541  {
542  cv::Mat rectified;
543  cv::remap(raw, rectified, mapX_, mapY_, interpolation);
544  return rectified;
545  }
546  else
547  {
548  UERROR("Cannot rectify image because the rectify map is not initialized.");
549  return raw.clone();
550  }
551 }
552 
553 //inspired from https://github.com/code-iai/iai_kinect2/blob/master/depth_registration/src/depth_registration_cpu.cpp
554 cv::Mat CameraModel::rectifyDepth(const cv::Mat & raw) const
555 {
556  UDEBUG("");
557  UASSERT(raw.type() == CV_16UC1);
558  if(!mapX_.empty() && !mapY_.empty())
559  {
560  cv::Mat rectified = cv::Mat::zeros(mapX_.rows, mapX_.cols, raw.type());
561  for(int y=0; y<mapX_.rows; ++y)
562  {
563  for(int x=0; x<mapX_.cols; ++x)
564  {
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)
571  {
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)
577  {
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)
584  {
585  //bilinear interpolation
586  float a = pt.x - (float)xL;
587  float c = pt.y - (float)yL;
588 
589  //http://stackoverflow.com/questions/13299409/how-to-get-the-image-pixel-at-real-locations-in-opencv
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;
593  }
594  }
595  }
596  }
597  }
598  return rectified;
599  }
600  else
601  {
602  UERROR("Cannot rectify image because the rectify map is not initialized.");
603  return raw.clone();
604  }
605 }
606 
607 // resulting 3D point is in /camera_link frame
608 void CameraModel::project(float u, float v, float depth, float & x, float & y, float & z) const
609 {
610  if(depth > 0.0f)
611  {
612  // Fill in XYZ
613  x = (u - cx()) * depth / fx();
614  y = (v - cy()) * depth / fy();
615  z = depth;
616  }
617  else
618  {
619  x = y = z = std::numeric_limits<float>::quiet_NaN();
620  }
621 }
622 // 3D point is in /camera_link frame
623 void CameraModel::reproject(float x, float y, float z, float & u, float & v) const
624 {
625  UASSERT(z!=0.0f);
626  float invZ = 1.0f/z;
627  u = (fx()*x)*invZ + cx();
628  v = (fy()*y)*invZ + cy();
629 }
630 void CameraModel::reproject(float x, float y, float z, int & u, int & v) const
631 {
632  UASSERT(z!=0.0f);
633  float invZ = 1.0f/z;
634  u = (fx()*x)*invZ + cx();
635  v = (fy()*y)*invZ + cy();
636 }
637 
638 bool CameraModel::inFrame(int u, int v) const
639 {
640  return uIsInBounds(u, 0, imageWidth()) && uIsInBounds(v, 0, imageHeight());
641 }
642 
643 } /* namespace rtabmap */
int imageWidth() const
Definition: CameraModel.h:113
void setImageSize(const cv::Size &size)
const cv::Size & imageSize() const
Definition: CameraModel.h:112
const std::string & name() const
Definition: CameraModel.h:93
f
bool uIsInBounds(const T &value, const T &low, const T &high)
Definition: UMath.h:934
bool inFrame(int u, int v) const
Transform localTransform_
Definition: CameraModel.h:145
bool save(const std::string &directory) const
GLM_FUNC_DECL genType e()
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
double verticalFOV() const
Basic mathematics functions.
Some conversion functions.
Definition: Features2d.h:41
bool uStrContains(const std::string &string, const std::string &substring)
Definition: UStl.h:787
cv::Mat D() const
Definition: CameraModel.h:104
cv::Mat R() const
Definition: CameraModel.h:105
#define UASSERT(condition)
double horizontalFOV() const
Wrappers of STL for convenient functions.
double cx() const
Definition: CameraModel.h:97
bool load(const std::string &directory, const std::string &cameraName)
bool isNull() const
Definition: Transform.cpp:107
GLM_FUNC_DECL genType floor(genType const &x)
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
double fy() const
Definition: CameraModel.h:96
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
Definition: CameraModel.h:82
CameraModel roi(const cv::Rect &roi) const
cv::Mat P() const
Definition: CameraModel.h:106
double cy() const
Definition: CameraModel.h:98
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
Definition: CameraModel.h:80
cv::Mat rectifyDepth(const cv::Mat &raw) const
#define UDEBUG(...)
double fx() const
Definition: CameraModel.h:95
bool exists()
Definition: UFile.h:104
double Tx() const
Definition: CameraModel.h:99
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
cv::Mat K() const
Definition: CameraModel.h:103
std::string UTILITE_EXP uFormat(const char *fmt,...)
int imageHeight() const
Definition: CameraModel.h:114
GLM_FUNC_DECL genType ceil(genType const &x)
CameraModel scaled(double scale) const
const Transform & localTransform() const
Definition: CameraModel.h:109
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:30