StereoCameraModel.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 
29 #include <rtabmap/core/Version.h>
32 #include <rtabmap/utilite/UFile.h>
34 #include <opencv2/imgproc/imgproc.hpp>
35 
36 #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)))
38 #endif
39 
40 namespace rtabmap {
41 
43  const std::string & name,
44  const cv::Size & imageSize1,
45  const cv::Mat & K1, const cv::Mat & D1, const cv::Mat & R1, const cv::Mat & P1,
46  const cv::Size & imageSize2,
47  const cv::Mat & K2, const cv::Mat & D2, const cv::Mat & R2, const cv::Mat & P2,
48  const cv::Mat & R, const cv::Mat & T, const cv::Mat & E, const cv::Mat & F,
49  const Transform & localTransform) :
50  leftSuffix_("left"),
51  rightSuffix_("right"),
52  left_(name+"_"+leftSuffix_, imageSize1, K1, D1, R1, P1, localTransform),
53  right_(name+"_"+rightSuffix_, imageSize2, K2, D2, R2, P2, localTransform),
54  name_(name),
55  R_(R),
56  T_(T),
57  E_(E),
58  F_(F)
59 {
60  UASSERT(R_.empty() || (R_.rows == 3 && R_.cols == 3 && R_.type() == CV_64FC1));
61  UASSERT(T_.empty() || (T_.rows == 3 && T_.cols == 1 && T_.type() == CV_64FC1));
62  UASSERT(E_.empty() || (E_.rows == 3 && E_.cols == 3 && E_.type() == CV_64FC1));
63  UASSERT(F_.empty() || (F_.rows == 3 && F_.cols == 3 && F_.type() == CV_64FC1));
64 }
65 
67  const std::string & name,
68  const CameraModel & leftCameraModel,
69  const CameraModel & rightCameraModel,
70  const cv::Mat & R,
71  const cv::Mat & T,
72  const cv::Mat & E,
73  const cv::Mat & F) :
74  leftSuffix_("left"),
75  rightSuffix_("right"),
76  left_(leftCameraModel),
77  right_(rightCameraModel),
78  name_(name),
79  R_(R),
80  T_(T),
81  E_(E),
82  F_(F)
83 {
84  left_.setName(name+"_"+getLeftSuffix());
85  right_.setName(name+"_"+getRightSuffix());
86  UASSERT(R_.empty() || (R_.rows == 3 && R_.cols == 3 && R_.type() == CV_64FC1));
87  UASSERT(T_.empty() || (T_.rows == 3 && T_.cols == 1 && T_.type() == CV_64FC1));
88  UASSERT(E_.empty() || (E_.rows == 3 && E_.cols == 3 && E_.type() == CV_64FC1));
89  UASSERT(F_.empty() || (F_.rows == 3 && F_.cols == 3 && F_.type() == CV_64FC1));
90 
91  if(!R_.empty() && !T_.empty())
92  {
93  UASSERT(leftCameraModel.isValidForRectification() && rightCameraModel.isValidForRectification());
94 
96  {
98  }
99  }
100 }
101 
103  const std::string & name,
104  const CameraModel & leftCameraModel,
105  const CameraModel & rightCameraModel,
106  const Transform & extrinsics) :
107  leftSuffix_("left"),
108  rightSuffix_("right"),
109  left_(leftCameraModel),
110  right_(rightCameraModel),
111  name_(name)
112 {
113  left_.setName(name+"_"+getLeftSuffix());
114  right_.setName(name+"_"+getRightSuffix());
115 
116  if(!extrinsics.isNull())
117  {
118  UASSERT(leftCameraModel.isValidForRectification() && rightCameraModel.isValidForRectification());
119 
120  extrinsics.rotationMatrix().convertTo(R_, CV_64FC1);
121  extrinsics.translationMatrix().convertTo(T_, CV_64FC1);
122 
124  {
126  }
127  }
128 }
129 
131  double fx,
132  double fy,
133  double cx,
134  double cy,
135  double baseline,
136  const Transform & localTransform,
137  const cv::Size & imageSize) :
138  leftSuffix_("left"),
139  rightSuffix_("right"),
140  left_(fx, fy, cx, cy, localTransform, 0, imageSize),
141  right_(fx, fy, cx, cy, localTransform, baseline*-fx, imageSize)
142 {
143 }
144 
145 //minimal to be saved
147  const std::string & name,
148  double fx,
149  double fy,
150  double cx,
151  double cy,
152  double baseline,
153  const Transform & localTransform,
154  const cv::Size & imageSize) :
155  leftSuffix_("left"),
156  rightSuffix_("right"),
157  left_(name+"_"+getLeftSuffix(), fx, fy, cx, cy, localTransform, 0, imageSize),
158  right_(name+"_"+getRightSuffix(), fx, fy, cx, cy, localTransform, baseline*-fx, imageSize),
159  name_(name)
160 {
161 }
162 
163 void StereoCameraModel::setName(const std::string & name, const std::string & leftSuffix, const std::string & rightSuffix)
164 {
165  name_=name;
166  leftSuffix_ = leftSuffix;
167  rightSuffix_ = rightSuffix;
170 }
171 
173 {
174  cv::Mat R1,R2,P1,P2,Q;
175  #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)))
176  bool fishEye = left_.D_raw().cols == 6;
177  // calibrate extrinsic
178  if(fishEye)
179  {
180  cv::Vec4d D_left(left_.D_raw().at<double>(0,0), left_.D_raw().at<double>(0,1), left_.D_raw().at<double>(0,4), left_.D_raw().at<double>(0,5));
181  cv::Vec4d D_right(right_.D_raw().at<double>(0,0), right_.D_raw().at<double>(0,1), right_.D_raw().at<double>(0,4), right_.D_raw().at<double>(0,5));
182 
184  left_.K_raw(), D_left,
185  right_.K_raw(), D_right,
186  left_.imageSize(), R_, T_, R1, R2, P1, P2, Q,
187  cv::CALIB_ZERO_DISPARITY, 0, left_.imageSize());
188 
189  // Re-zoom to original focal distance
190  if(P1.at<double>(0,0) < 0)
191  {
192  P1.at<double>(0,0) *= -1;
193  P1.at<double>(1,1) *= -1;
194  }
195  if(P2.at<double>(0,0) < 0)
196  {
197  P2.at<double>(0,0) *= -1;
198  P2.at<double>(1,1) *= -1;
199  }
200  if(P2.at<double>(0,3) > 0)
201  {
202  P2.at<double>(0,3) *= -1;
203  }
204  P2.at<double>(0,3) = P2.at<double>(0,3) * left_.K_raw().at<double>(0,0) / P2.at<double>(0,0);
205  P1.at<double>(0,0) = P1.at<double>(1,1) = left_.K_raw().at<double>(0,0);
206  P2.at<double>(0,0) = P2.at<double>(1,1) = left_.K_raw().at<double>(0,0);
207  }
208  else
209 #endif
210  {
211 
212  cv::stereoRectify(
213  left_.K_raw(), left_.D_raw(),
214  right_.K_raw(), right_.D_raw(),
215  left_.imageSize(), R_, T_, R1, R2, P1, P2, Q,
216  cv::CALIB_ZERO_DISPARITY, 0, left_.imageSize());
217  }
218 
219  left_ = CameraModel(left_.name(), left_.imageSize(), left_.K_raw(), left_.D_raw(), R1, P1, left_.localTransform());
220  right_ = CameraModel(right_.name(), right_.imageSize(), right_.K_raw(), right_.D_raw(), R2, P2, right_.localTransform());
221 }
222 
223 bool StereoCameraModel::load(const std::string & directory, const std::string & cameraName, bool ignoreStereoTransform)
224 {
225  name_ = cameraName;
226  bool leftLoaded = left_.load(directory, cameraName+"_"+getLeftSuffix());
227  bool rightLoaded = right_.load(directory, cameraName+"_"+getRightSuffix());
228  if(leftLoaded && rightLoaded)
229  {
230  if(ignoreStereoTransform)
231  {
232  return true;
233  }
234  //load rotation, translation
235  R_ = cv::Mat();
236  T_ = cv::Mat();
237  E_ = cv::Mat();
238  F_ = cv::Mat();
239 
240  std::string filePath = directory+"/"+cameraName+"_pose.yaml";
241  if(UFile::exists(filePath))
242  {
243  UINFO("Reading stereo calibration file \"%s\"", filePath.c_str());
244  cv::FileStorage fs(filePath, cv::FileStorage::READ);
245 
246  cv::FileNode n;
247 
248  n = fs["camera_name"];
249  if(n.type() != cv::FileNode::NONE)
250  {
251  name_ = (int)n;
252  }
253  else
254  {
255  UWARN("Missing \"camera_name\" field in \"%s\"", filePath.c_str());
256  }
257 
258  // import from ROS calibration format
259  n = fs["rotation_matrix"];
260  if(n.type() != cv::FileNode::NONE)
261  {
262  int rows = (int)n["rows"];
263  int cols = (int)n["cols"];
264  std::vector<double> data;
265  n["data"] >> data;
266  UASSERT(rows*cols == (int)data.size());
267  UASSERT(rows == 3 && cols == 3);
268  R_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
269  }
270  else
271  {
272  UWARN("Missing \"rotation_matrix\" field in \"%s\"", filePath.c_str());
273  }
274 
275  n = fs["translation_matrix"];
276  if(n.type() != cv::FileNode::NONE)
277  {
278  int rows = (int)n["rows"];
279  int cols = (int)n["cols"];
280  std::vector<double> data;
281  n["data"] >> data;
282  UASSERT(rows*cols == (int)data.size());
283  UASSERT(rows == 3 && cols == 1);
284  T_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
285  }
286  else
287  {
288  UWARN("Missing \"translation_matrix\" field in \"%s\"", filePath.c_str());
289  }
290 
291  n = fs["essential_matrix"];
292  if(n.type() != cv::FileNode::NONE)
293  {
294  int rows = (int)n["rows"];
295  int cols = (int)n["cols"];
296  std::vector<double> data;
297  n["data"] >> data;
298  UASSERT(rows*cols == (int)data.size());
299  UASSERT(rows == 3 && cols == 3);
300  E_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
301  }
302  else
303  {
304  UWARN("Missing \"essential_matrix\" field in \"%s\"", filePath.c_str());
305  }
306 
307  n = fs["fundamental_matrix"];
308  if(n.type() != cv::FileNode::NONE)
309  {
310  int rows = (int)n["rows"];
311  int cols = (int)n["cols"];
312  std::vector<double> data;
313  n["data"] >> data;
314  UASSERT(rows*cols == (int)data.size());
315  UASSERT(rows == 3 && cols == 3);
316  F_ = cv::Mat(rows, cols, CV_64FC1, data.data()).clone();
317  }
318  else
319  {
320  UWARN("Missing \"fundamental_matrix\" field in \"%s\"", filePath.c_str());
321  }
322 
323  fs.release();
324 
325  return true;
326  }
327  else
328  {
329  UWARN("Could not load stereo calibration file \"%s\".", filePath.c_str());
330  }
331  }
332  return false;
333 }
334 bool StereoCameraModel::save(const std::string & directory, bool ignoreStereoTransform) const
335 {
336  if(left_.save(directory) && right_.save(directory))
337  {
338  if(ignoreStereoTransform)
339  {
340  return true;
341  }
342  return saveStereoTransform(directory);
343  }
344  return false;
345 }
346 
347 bool StereoCameraModel::saveStereoTransform(const std::string & directory) const
348 {
349  std::string filePath = directory+"/"+name_+"_pose.yaml";
350  if(!filePath.empty() && (!R_.empty() && !T_.empty()))
351  {
352  UINFO("Saving stereo calibration to file \"%s\"", filePath.c_str());
353  cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
354 
355  // export in ROS calibration format
356 
357  if(!name_.empty())
358  {
359  fs << "camera_name" << name_;
360  }
361 
362  if(!R_.empty())
363  {
364  fs << "rotation_matrix" << "{";
365  fs << "rows" << R_.rows;
366  fs << "cols" << R_.cols;
367  fs << "data" << std::vector<double>((double*)R_.data, ((double*)R_.data)+(R_.rows*R_.cols));
368  fs << "}";
369  }
370 
371  if(!T_.empty())
372  {
373  fs << "translation_matrix" << "{";
374  fs << "rows" << T_.rows;
375  fs << "cols" << T_.cols;
376  fs << "data" << std::vector<double>((double*)T_.data, ((double*)T_.data)+(T_.rows*T_.cols));
377  fs << "}";
378  }
379 
380  if(!E_.empty())
381  {
382  fs << "essential_matrix" << "{";
383  fs << "rows" << E_.rows;
384  fs << "cols" << E_.cols;
385  fs << "data" << std::vector<double>((double*)E_.data, ((double*)E_.data)+(E_.rows*E_.cols));
386  fs << "}";
387  }
388 
389  if(!F_.empty())
390  {
391  fs << "fundamental_matrix" << "{";
392  fs << "rows" << F_.rows;
393  fs << "cols" << F_.cols;
394  fs << "data" << std::vector<double>((double*)F_.data, ((double*)F_.data)+(F_.rows*F_.cols));
395  fs << "}";
396  }
397 
398  fs.release();
399 
400  return true;
401  }
402  else
403  {
404  UERROR("Failed saving stereo extrinsics (they are null).");
405  }
406  return false;
407 }
408 
409 std::vector<unsigned char> StereoCameraModel::serialize() const
410 {
411  std::vector<unsigned char> leftData = left_.serialize();
412  std::vector<unsigned char> rightData = right_.serialize();
413 
414  const int headerSize = 10;
415  int header[headerSize] = {
416  RTABMAP_VERSION_MAJOR, RTABMAP_VERSION_MINOR, RTABMAP_VERSION_PATCH, // 0,1,2
417  1, //stereo // 3
418  (int)R_.total(), (int)T_.total(), (int)E_.total(), (int)F_.total(), // 4,5,6,7
419  (int)leftData.size(), (int)rightData.size()}; // 8,9
420  UDEBUG("Header: %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]);
421  std::vector<unsigned char> data(
422  sizeof(int)*headerSize +
423  sizeof(double)*(R_.total()+T_.total()+E_.total()+F_.total()) +
424  leftData.size() + rightData.size());
425  memcpy(data.data(), header, sizeof(int)*headerSize);
426  int index = sizeof(int)*headerSize;
427  if(!R_.empty())
428  {
429  memcpy(data.data()+index, R_.data, sizeof(double)*(R_.total()));
430  index+=sizeof(double)*(R_.total());
431  }
432  if(!T_.empty())
433  {
434  memcpy(data.data()+index, T_.data, sizeof(double)*(T_.total()));
435  index+=sizeof(double)*(T_.total());
436  }
437  if(!E_.empty())
438  {
439  memcpy(data.data()+index, E_.data, sizeof(double)*(E_.total()));
440  index+=sizeof(double)*(E_.total());
441  }
442  if(!F_.empty())
443  {
444  memcpy(data.data()+index, F_.data, sizeof(double)*(F_.total()));
445  index+=sizeof(double)*(F_.total());
446  }
447  if(leftData.size())
448  {
449  memcpy(data.data()+index, leftData.data(), leftData.size());
450  index+=leftData.size();
451  }
452  if(rightData.size())
453  {
454  memcpy(data.data()+index, rightData.data(), rightData.size());
455  index+=rightData.size();
456  }
457  return data;
458 }
459 
460 unsigned int StereoCameraModel::deserialize(const std::vector<unsigned char>& data)
461 {
462  return deserialize(data.data(), data.size());
463 }
464 unsigned int StereoCameraModel::deserialize(const unsigned char * data, unsigned int dataSize)
465 {
466  *this = StereoCameraModel();
467  int headerSize = 10;
468  if(dataSize >= sizeof(int)*headerSize)
469  {
470  int iR = 4;
471  int iT = 5;
472  int iE = 6;
473  int iF = 7;
474  int iLeft = 8;
475  int iRight = 9;
476  const int * header = (const int *)data;
477  UDEBUG("Header: %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]);
478  int type = header[3];
479  if(type==1)
480  {
481  unsigned int requiredDataSize = sizeof(int)*headerSize +
482  sizeof(double)*(header[iR]+header[iT]+header[iE]+header[iF]) +
483  header[iLeft] + header[iRight];
484  UASSERT_MSG(dataSize >= requiredDataSize,
485  uFormat("dataSize=%d != required=%d (header: version %d.%d.%d type=%d R=%d T=%d E=%d F=%d Left=%d Right=%d)",
486  dataSize,
487  requiredDataSize,
488  header[0], header[1], header[2], header[3],
489  header[iR], header[iT], header[iE],header[iF], header[iLeft], header[iRight]).c_str());
490 
491  unsigned int index = sizeof(int)*headerSize;
492 
493  if(header[iR] != 0)
494  {
495  UASSERT(header[iR] == 9);
496  R_ = cv::Mat(3, 3, CV_64FC1, (void*)(data+index)).clone();
497  index+=sizeof(double)*(R_.total());
498  }
499 
500  if(header[iT] != 0)
501  {
502  UASSERT(header[iT] == 3);
503  T_ = cv::Mat(3, 1, CV_64FC1, (void*)(data+index)).clone();
504  index+=sizeof(double)*(T_.total());
505  }
506 
507  if(header[iE] != 0)
508  {
509  UASSERT(header[iE] == 9);
510  E_ = cv::Mat(3, 3, CV_64FC1, (void*)(data+index)).clone();
511  index+=sizeof(double)*(E_.total());
512  }
513 
514  if(header[iF] != 0)
515  {
516  UASSERT(header[iF] == 9);
517  F_ = cv::Mat(3, 3, CV_64FC1, (void*)(data+index)).clone();
518  index+=sizeof(double)*(F_.total());
519  }
520 
521  if(header[iLeft] != 0)
522  {
523  index += left_.deserialize((data+index), header[iLeft]);
524  }
525 
526  if(header[iRight] != 0)
527  {
528  index += right_.deserialize((data+index), header[iRight]);
529  }
530 
531  UASSERT(index <= dataSize);
532 
533  return index;
534  }
535  else
536  {
537  UERROR("Serialized calibration is not stereo (type=%d), use the appropriate class matching the type to deserialize.", type);
538  }
539  }
540  UERROR("Wrong serialized calibration data format detected (size in bytes=%d)! Cannot deserialize the data.", (int)dataSize);
541  return 0;
542 }
543 
545 {
546  left_ = left_.scaled(scale);
547  right_ = right_.scaled(scale);
548 }
549 
550 void StereoCameraModel::roi(const cv::Rect & roi)
551 {
552  left_ = left_.roi(roi);
553  right_ = right_.roi(roi);
554 }
555 
556 float StereoCameraModel::computeDepth(float disparity) const
557 {
558  //depth = baseline * f / (disparity + cx1-cx0);
559  UASSERT(this->isValidForProjection());
560  if(disparity == 0.0f)
561  {
562  return 0.0f;
563  }
564  return baseline() * left().fx() / (disparity + right().cx() - left().cx());
565 }
566 
567 float StereoCameraModel::computeDisparity(float depth) const
568 {
569  // disparity = (baseline * fx / depth) - (cx1-cx0);
570  UASSERT(this->isValidForProjection());
571  if(depth == 0.0f)
572  {
573  return 0.0f;
574  }
575  return baseline() * left().fx() / depth - right().cx() + left().cx();
576 }
577 
578 float StereoCameraModel::computeDisparity(unsigned short depth) const
579 {
580  // disparity = (baseline * fx / depth) - (cx1-cx0);
581  UASSERT(this->isValidForProjection());
582  if(depth == 0)
583  {
584  return 0.0f;
585  }
586  return baseline() * left().fx() / (float(depth)/1000.0f) - right().cx() + left().cx();
587 }
588 
590 {
591  if(!R_.empty() && !T_.empty())
592  {
593  return Transform(
594  R_.at<double>(0,0), R_.at<double>(0,1), R_.at<double>(0,2), T_.at<double>(0),
595  R_.at<double>(1,0), R_.at<double>(1,1), R_.at<double>(1,2), T_.at<double>(1),
596  R_.at<double>(2,0), R_.at<double>(2,1), R_.at<double>(2,2), T_.at<double>(2));
597  }
598  return Transform();
599 }
600 
601 } /* namespace rtabmap */
int imageWidth() const
Definition: CameraModel.h:120
cv::Mat K_raw() const
Definition: CameraModel.h:108
const cv::Size & imageSize() const
Definition: CameraModel.h:119
const cv::Mat & R() const
const std::string & name() const
Definition: CameraModel.h:100
f
Transform stereoTransform() const
cv::Mat rotationMatrix() const
Definition: Transform.cpp:217
std::vector< unsigned char > serialize() const
cv::Mat translationMatrix() const
Definition: Transform.cpp:222
bool save(const std::string &directory) const
unsigned int deserialize(const std::vector< unsigned char > &data)
const cv::Mat & F() const
bool load(const std::string &filePath)
std_msgs::Header * header(M &m)
Some conversion functions.
const std::string & getRightSuffix() const
float computeDepth(float disparity) const
float computeDisparity(float depth) const
#define UASSERT(condition)
const CameraModel & left() const
double cx() const
Definition: CameraModel.h:104
bool isNull() const
Definition: Transform.cpp:107
std::vector< unsigned char > serialize() const
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
const cv::Mat & T() const
const cv::Mat & E() const
bool saveStereoTransform(const std::string &directory) const
void stereoRectifyFisheye(cv::InputArray _cameraMatrix1, cv::InputArray _distCoeffs1, cv::InputArray _cameraMatrix2, cv::InputArray _distCoeffs2, cv::Size imageSize, cv::InputArray _Rmat, cv::InputArray _Tmat, cv::OutputArray _Rmat1, cv::OutputArray _Rmat2, cv::OutputArray _Pmat1, cv::OutputArray _Pmat2, cv::OutputArray _Qmat, int flags, double alpha, cv::Size newImageSize)
bool isValidForRectification() const
Definition: CameraModel.h:89
bool save(const std::string &directory, bool ignoreStereoTransform=true) const
CameraModel roi(const cv::Rect &roi) const
void roi(const cv::Rect &roi)
bool load(const std::string &directory, const std::string &cameraName, bool ignoreStereoTransform=true)
#define UDEBUG(...)
double fx() const
Definition: CameraModel.h:102
const CameraModel & right() const
bool exists()
Definition: UFile.h:104
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
unsigned int deserialize(const std::vector< unsigned char > &data)
void setName(const std::string &name, const std::string &leftSuffix="left", const std::string &rightSuffix="right")
const std::string & getLeftSuffix() const
cv::Mat D_raw() const
Definition: CameraModel.h:109
const Transform & localTransform() const
std::string UTILITE_EXP uFormat(const char *fmt,...)
void setName(const std::string &name)
Definition: CameraModel.h:99
int imageHeight() const
Definition: CameraModel.h:121
CameraModel scaled(double scale) const
const Transform & localTransform() const
Definition: CameraModel.h:116
const std::string & name() const
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:06