OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
PinholeCamera.hpp
Go to the documentation of this file.
1 /*********************************************************************************
2  * OKVIS - Open Keyframe-based Visual-Inertial SLAM
3  * Copyright (c) 2015, Autonomous Systems Lab / ETH Zurich
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  *
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of Autonomous Systems Lab / ETH Zurich nor the names of
14  * its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: Jan 28, 2015
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  * Modified: Andreas Forster (an.forster@gmail.com)
32  *********************************************************************************/
33 
42 // \brief okvis Main namespace of this package.
43 namespace okvis {
44 // \brief cameras Namespace for camera-related functionality.
45 namespace cameras {
46 
47 template<class DISTORTION_T>
49  int imageHeight,
50  double focalLengthU,
51  double focalLengthV,
52  double imageCenterU,
53  double imageCenterV,
54  const distortion_t & distortion,
55  uint64_t id)
56  : CameraBase(imageWidth, imageHeight, id),
57  distortion_(distortion),
58  fu_(focalLengthU),
59  fv_(focalLengthV),
60  cu_(imageCenterU),
61  cv_(imageCenterV)
62 {
63  intrinsics_[0] = fu_; //< focalLengthU
64  intrinsics_[1] = fv_; //< focalLengthV
65  intrinsics_[2] = cu_; //< imageCenterU
66  intrinsics_[3] = cv_; //< imageCenterV
67  one_over_fu_ = 1.0 / fu_; //< 1.0 / fu_
68  one_over_fv_ = 1.0 / fv_; //< 1.0 / fv_
69  fu_over_fv_ = fu_ / fv_; //< fu_ / fv_
70 }
71 
72 // overwrite all intrinsics - use with caution !
73 template<class DISTORTION_T>
75  const Eigen::VectorXd & intrinsics)
76 {
77  if (intrinsics.cols() != NumIntrinsics) {
78  return false;
79  }
80  intrinsics_ = intrinsics;
81  fu_ = intrinsics[0]; //< focalLengthU
82  fv_ = intrinsics[1]; //< focalLengthV
83  cu_ = intrinsics[2]; //< imageCenterU
84  cv_ = intrinsics[3]; //< imageCenterV
85  distortion_.setParameters(
86  intrinsics.tail<distortion_t::NumDistortionIntrinsics>());
87  one_over_fu_ = 1.0 / fu_; //< 1.0 / fu_
88  one_over_fv_ = 1.0 / fv_; //< 1.0 / fv_
89  fu_over_fv_ = fu_ / fv_; //< fu_ / fv_
90  return true;
91 }
92 
93 template<class DISTORTION_T>
94 void PinholeCamera<DISTORTION_T>::getIntrinsics(Eigen::VectorXd & intrinsics) const
95  {
96  intrinsics = intrinsics_;
97  Eigen::VectorXd distortionIntrinsics;
98  if(distortion_t::NumDistortionIntrinsics > 0) {
99  distortion_.getParameters(distortionIntrinsics);
100  intrinsics.tail<distortion_t::NumDistortionIntrinsics>() = distortionIntrinsics;
101  }
102  }
103 
105 // Methods to project points
106 
107 // Projects a Euclidean point to a 2d image point (projection).
108 template<class DISTORTION_T>
110  const Eigen::Vector3d & point, Eigen::Vector2d * imagePoint) const
111 {
112  // handle singularity
113  if (fabs(point[2]) < 1.0e-12) {
115  }
116 
117  // projection
118  Eigen::Vector2d imagePointUndistorted;
119  const double rz = 1.0 / point[2];
120  imagePointUndistorted[0] = point[0] * rz;
121  imagePointUndistorted[1] = point[1] * rz;
122 
123  // distortion
124  Eigen::Vector2d imagePoint2;
125  if (!distortion_.distort(imagePointUndistorted, &imagePoint2)) {
127  }
128 
129  // scale and offset
130  (*imagePoint)[0] = fu_ * imagePoint2[0] + cu_;
131  (*imagePoint)[1] = fv_ * imagePoint2[1] + cv_;
132 
133  if (!CameraBase::isInImage(*imagePoint)) {
135  }
136  if (CameraBase::isMasked(*imagePoint)) {
138  }
139  if(point[2]>0.0){
141  } else {
143  }
144 }
145 
146 // Projects a Euclidean point to a 2d image point (projection).
147 template<class DISTORTION_T>
149  const Eigen::Vector3d & point, Eigen::Vector2d * imagePoint,
150  Eigen::Matrix<double, 2, 3> * pointJacobian,
151  Eigen::Matrix2Xd * intrinsicsJacobian) const
152 {
153  // handle singularity
154  if (fabs(point[2]) < 1.0e-12) {
156  }
157 
158  // projection
159  Eigen::Vector2d imagePointUndistorted;
160  const double rz = 1.0 / point[2];
161  double rz2 = rz * rz;
162  imagePointUndistorted[0] = point[0] * rz;
163  imagePointUndistorted[1] = point[1] * rz;
164 
165  Eigen::Matrix<double, 2, 3> pointJacobianProjection;
166  Eigen::Matrix2Xd intrinsicsJacobianProjection;
167  Eigen::Matrix2d distortionJacobian;
168  Eigen::Matrix2Xd intrinsicsJacobianDistortion;
169  Eigen::Vector2d imagePoint2;
170 
171  bool distortionSuccess;
172  if (intrinsicsJacobian) {
173  // get both Jacobians
174  intrinsicsJacobian->resize(2, NumIntrinsics);
175 
176  distortionSuccess = distortion_.distort(imagePointUndistorted, &imagePoint2,
177  &distortionJacobian,
178  &intrinsicsJacobianDistortion);
179  // compute the intrinsics Jacobian
180  intrinsicsJacobian->template topLeftCorner<2, 2>() =
181  imagePoint2.asDiagonal();
182  intrinsicsJacobian->template block<2, 2>(0,2) = Eigen::Matrix2d::Identity();
183 
184  if (distortion_t::NumDistortionIntrinsics > 0) {
185  intrinsicsJacobian
186  ->template bottomRightCorner<2, distortion_t::NumDistortionIntrinsics>() =
187  Eigen::Vector2d(fu_, fv_).asDiagonal() * intrinsicsJacobianDistortion; // chain rule
188  }
189  } else {
190  // only get point Jacobian
191  distortionSuccess = distortion_.distort(imagePointUndistorted, &imagePoint2,
192  &distortionJacobian);
193  }
194 
195  // compute the point Jacobian in any case
196  Eigen::Matrix<double, 2, 3> & J = *pointJacobian;
197  J(0, 0) = fu_ * distortionJacobian(0, 0) * rz;
198  J(0, 1) = fu_ * distortionJacobian(0, 1) * rz;
199  J(0, 2) = -fu_
200  * (point[0] * distortionJacobian(0, 0)
201  + point[1] * distortionJacobian(0, 1)) * rz2;
202  J(1, 0) = fv_ * distortionJacobian(1, 0) * rz;
203  J(1, 1) = fv_ * distortionJacobian(1, 1) * rz;
204  J(1, 2) = -fv_
205  * (point[0] * distortionJacobian(1, 0)
206  + point[1] * distortionJacobian(1, 1)) * rz2;
207 
208  // scale and offset
209  (*imagePoint)[0] = fu_ * imagePoint2[0] + cu_;
210  (*imagePoint)[1] = fv_ * imagePoint2[1] + cv_;
211 
212  if (!distortionSuccess) {
214  }
215  if (!CameraBase::isInImage(*imagePoint)) {
217  }
218  if (CameraBase::isMasked(*imagePoint)) {
220  }
221  if(point[2]>0.0){
223  } else {
225  }
226 }
227 
228 // Projects a Euclidean point to a 2d image point (projection).
229 template<class DISTORTION_T>
231  const Eigen::Vector3d & point, const Eigen::VectorXd & parameters,
232  Eigen::Vector2d * imagePoint, Eigen::Matrix<double, 2, 3> * pointJacobian,
233  Eigen::Matrix2Xd * intrinsicsJacobian) const
234 {
235  // handle singularity
236  if (fabs(point[2]) < 1.0e-12) {
238  }
239 
240  // parse parameters into human readable form
241  const double fu = parameters[0];
242  const double fv = parameters[1];
243  const double cu = parameters[2];
244  const double cv = parameters[3];
245 
246  Eigen::VectorXd distortionParameters;
247  if (distortion_t::NumDistortionIntrinsics > 0) {
248  distortionParameters = parameters
249  .template tail<distortion_t::NumDistortionIntrinsics>();
250  }
251 
252  // projection
253  Eigen::Vector2d imagePointUndistorted;
254  const double rz = 1.0 / point[2];
255  double rz2 = rz * rz;
256  imagePointUndistorted[0] = point[0] * rz;
257  imagePointUndistorted[1] = point[1] * rz;
258 
259  Eigen::Matrix<double, 2, 3> pointJacobianProjection;
260  Eigen::Matrix2Xd intrinsicsJacobianProjection;
261  Eigen::Matrix2d distortionJacobian;
262  Eigen::Matrix2Xd intrinsicsJacobianDistortion;
263  Eigen::Vector2d imagePoint2;
264 
265  bool distortionSuccess;
266  if (intrinsicsJacobian) {
267  // get both Jacobians
268  intrinsicsJacobian->resize(2, NumIntrinsics);
269 
270  distortionSuccess = distortion_.distortWithExternalParameters(imagePointUndistorted,
271  distortionParameters, &imagePoint2,
272  &distortionJacobian,
273  &intrinsicsJacobianDistortion);
274  // compute the intrinsics Jacobian
275  intrinsicsJacobian->template topLeftCorner<2, 2>() =
276  imagePoint2.asDiagonal();
277  intrinsicsJacobian->template block<2, 2>(0,2) = Eigen::Matrix2d::Identity();
278 
279  if (distortion_t::NumDistortionIntrinsics > 0) {
280  intrinsicsJacobian
281  ->template bottomRightCorner<2, distortion_t::NumDistortionIntrinsics>() =
282  Eigen::Vector2d(fu, fv).asDiagonal() * intrinsicsJacobianDistortion; // chain rule
283  }
284  } else {
285  // only get point Jacobian
286  distortionSuccess = distortion_.distortWithExternalParameters(imagePointUndistorted,
287  distortionParameters, &imagePoint2,
288  &distortionJacobian);
289  }
290 
291  // compute the point Jacobian, if requested
292  if(pointJacobian) {
293  Eigen::Matrix<double, 2, 3> & J = *pointJacobian;
294  J(0, 0) = fu * distortionJacobian(0, 0) * rz;
295  J(0, 1) = fu * distortionJacobian(0, 1) * rz;
296  J(0, 2) = -fu
297  * (point[0] * distortionJacobian(0, 0)
298  + point[1] * distortionJacobian(0, 1)) * rz2;
299  J(1, 0) = fv * distortionJacobian(1, 0) * rz;
300  J(1, 1) = fv * distortionJacobian(1, 1) * rz;
301  J(1, 2) = -fv
302  * (point[0] * distortionJacobian(1, 0)
303  + point[1] * distortionJacobian(1, 1)) * rz2;
304  }
305 
306  // scale and offset
307  (*imagePoint)[0] = fu * imagePoint2[0] + cu;
308  (*imagePoint)[1] = fv * imagePoint2[1] + cv;
309 
310  if (!distortionSuccess) {
312  }
313  if (!CameraBase::isInImage(*imagePoint)) {
315  }
316  if (CameraBase::isMasked(*imagePoint)) {
318  }
319  if(point[2]>0.0){
321  } else {
323  }
324 }
325 
326 // Projects Euclidean points to 2d image points (projection) in a batch.
327 template<class DISTORTION_T>
329  const Eigen::Matrix3Xd & points, Eigen::Matrix2Xd * imagePoints,
330  std::vector<CameraBase::ProjectionStatus> * stati) const
331 {
332  const int numPoints = points.cols();
333  for (int i = 0; i < numPoints; ++i) {
334  Eigen::Vector3d point = points.col(i);
335  Eigen::Vector2d imagePoint;
336  CameraBase::ProjectionStatus status = project(point, &imagePoint);
337  imagePoints->col(i) = imagePoint;
338  if(stati)
339  stati->push_back(status);
340  }
341 }
342 
343 // Projects a point in homogenous coordinates to a 2d image point (projection).
344 template<class DISTORTION_T>
346  const Eigen::Vector4d & point, Eigen::Vector2d * imagePoint) const
347 {
348  Eigen::Vector3d head = point.head<3>();
349  if (point[3] < 0) {
350  return project(-head, imagePoint);
351  } else {
352  return project(head, imagePoint);
353  }
354 }
355 
356 // Projects a point in homogenous coordinates to a 2d image point (projection).
357 template<class DISTORTION_T>
359  const Eigen::Vector4d & point, Eigen::Vector2d * imagePoint,
360  Eigen::Matrix<double, 2, 4> * pointJacobian,
361  Eigen::Matrix2Xd * intrinsicsJacobian) const
362 {
363  Eigen::Vector3d head = point.head<3>();
364  Eigen::Matrix<double, 2, 3> pointJacobian3;
366  if (point[3] < 0) {
367  status = project(-head, imagePoint,
368  &pointJacobian3,
369  intrinsicsJacobian);
370  } else {
371  status = project(head, imagePoint,
372  &pointJacobian3,
373  intrinsicsJacobian);
374  }
375  pointJacobian->template bottomRightCorner<2, 1>() = Eigen::Vector2d::Zero();
376  pointJacobian->template topLeftCorner<2, 3>() = pointJacobian3;
377  return status;
378 }
379 
380 // Projects a point in homogenous coordinates to a 2d image point (projection).
381 template<class DISTORTION_T>
383  const Eigen::Vector4d & point, const Eigen::VectorXd & parameters,
384  Eigen::Vector2d * imagePoint, Eigen::Matrix<double, 2, 4> * pointJacobian,
385  Eigen::Matrix2Xd * intrinsicsJacobian) const
386 {
387  Eigen::Vector3d head = point.head<3>();
388  Eigen::Matrix<double, 2, 3> pointJacobian3;
390  if (point[3] < 0) {
391  status = projectWithExternalParameters(-head, parameters, imagePoint,
392  &pointJacobian3,
393  intrinsicsJacobian);
394  } else {
395  status = projectWithExternalParameters(head, parameters, imagePoint,
396  &pointJacobian3,
397  intrinsicsJacobian);
398  }
399  pointJacobian->template bottomRightCorner<2, 1>() = Eigen::Vector2d::Zero();
400  pointJacobian->template topLeftCorner<2, 3>() = pointJacobian3;
401  return status;
402 }
403 
404 // Projects points in homogenous coordinates to 2d image points (projection) in a batch.
405 template<class DISTORTION_T>
407  const Eigen::Matrix4Xd & points, Eigen::Matrix2Xd * imagePoints,
408  std::vector<ProjectionStatus> * stati) const
409 {
410  const int numPoints = points.cols();
411  for (int i = 0; i < numPoints; ++i) {
412  Eigen::Vector4d point = points.col(i);
413  Eigen::Vector2d imagePoint;
414  CameraBase::ProjectionStatus status = projectHomogeneous(point, &imagePoint);
415  imagePoints->col(i) = imagePoint;
416  if(stati)
417  stati->push_back(status);
418  }
419 }
420 
422 // Methods to backproject points
423 
424 // Back-project a 2d image point into Euclidean space (direction vector).
425 template<class DISTORTION_T>
427  const Eigen::Vector2d & imagePoint, Eigen::Vector3d * direction) const
428 {
429  // unscale and center
430  Eigen::Vector2d imagePoint2;
431  imagePoint2[0] = (imagePoint[0] - cu_) * one_over_fu_;
432  imagePoint2[1] = (imagePoint[1] - cv_) * one_over_fv_;
433 
434  // undistort
435  Eigen::Vector2d undistortedImagePoint;
436  bool success = distortion_.undistort(imagePoint2, &undistortedImagePoint);
437 
438  // project 1 into z direction
439  (*direction)[0] = undistortedImagePoint[0];
440  (*direction)[1] = undistortedImagePoint[1];
441  (*direction)[2] = 1.0;
442 
443  return success;
444 }
445 
446 // Back-project a 2d image point into Euclidean space (direction vector).
447 template<class DISTORTION_T>
449  const Eigen::Vector2d & imagePoint, Eigen::Vector3d * direction,
450  Eigen::Matrix<double, 3, 2> * pointJacobian) const
451 {
452  // unscale and center
453  Eigen::Vector2d imagePoint2;
454  imagePoint2[0] = (imagePoint[0] - cu_) * one_over_fu_;
455  imagePoint2[1] = (imagePoint[1] - cv_) * one_over_fv_;
456 
457  // undistort
458  Eigen::Vector2d undistortedImagePoint;
459  Eigen::Matrix2d pointJacobianUndistortion;
460  bool success = distortion_.undistort(imagePoint2, &undistortedImagePoint,
461  &pointJacobianUndistortion);
462 
463  // project 1 into z direction
464  (*direction)[0] = undistortedImagePoint[0];
465  (*direction)[1] = undistortedImagePoint[1];
466  (*direction)[2] = 1.0;
467 
468  // Jacobian w.r.t. imagePoint
469  Eigen::Matrix<double, 3, 2> outProjectJacobian =
470  Eigen::Matrix<double, 3, 2>::Zero();
471  outProjectJacobian(0, 0) = one_over_fu_;
472  outProjectJacobian(1, 1) = one_over_fv_;
473 
474  (*pointJacobian) = outProjectJacobian * pointJacobianUndistortion; // chain rule
475 
476  return success;
477 }
478 
479 // Back-project 2d image points into Euclidean space (direction vectors).
480 template<class DISTORTION_T>
482  const Eigen::Matrix2Xd & imagePoints, Eigen::Matrix3Xd * directions,
483  std::vector<bool> * success) const
484 {
485  const int numPoints = imagePoints.cols();
486  directions->row(3) = Eigen::VectorXd::Ones(numPoints);
487  for (int i = 0; i < numPoints; ++i) {
488  Eigen::Vector2d imagePoint = imagePoints.col(i);
489  Eigen::Vector3d point;
490  bool suc = backProject(imagePoint, &point);
491  if(success)
492  success->push_back(suc);
493  directions->col(i) = point;
494  }
495  return true;
496 }
497 
498 // Back-project a 2d image point into homogeneous point (direction vector).
499 template<class DISTORTION_T>
501  const Eigen::Vector2d & imagePoint, Eigen::Vector4d * direction) const
502 {
503  Eigen::Vector3d ray;
504  bool success = backProject(imagePoint, &ray);
505  direction->template head<3>() = ray;
506  (*direction)[4] = 1.0; // arbitrary
507  return success;
508 }
509 
510 // Back-project a 2d image point into homogeneous point (direction vector).
511 template<class DISTORTION_T>
513  const Eigen::Vector2d & imagePoint, Eigen::Vector4d * direction,
514  Eigen::Matrix<double, 4, 2> * pointJacobian) const
515 {
516  Eigen::Vector3d ray;
517  Eigen::Matrix<double, 3, 2> pointJacobian3;
518  bool success = backProject(imagePoint, &ray, &pointJacobian3);
519  direction->template head<3>() = ray;
520  (*direction)[4] = 1.0; // arbitrary
521  pointJacobian->template bottomRightCorner<1,2>() = Eigen::Vector2d::Zero();
522  pointJacobian->template topLeftCorner<3, 2>() = pointJacobian3;
523  return success;
524 }
525 
526 // Back-project 2d image points into homogeneous points (direction vectors).
527 template<class DISTORTION_T>
529  const Eigen::Matrix2Xd & imagePoints, Eigen::Matrix4Xd * directions,
530  std::vector<bool> * success) const
531 {
532  const int numPoints = imagePoints.cols();
533  directions->row(3) = Eigen::VectorXd::Ones(numPoints);
534  for (int i = 0; i < numPoints; ++i) {
535  Eigen::Vector2d imagePoint = imagePoints.col(i);
536  Eigen::Vector3d point;
537  bool suc = backProject(imagePoint, &point);
538  if(success)
539  success->push_back(suc);
540  directions->template block<3, 1>(0, i) = point;
541  }
542  return true;
543 }
544 
545 } // namespace cameras
546 } // namespace okvis
ProjectionStatus
Definition: CameraBase.hpp:67
PinholeCamera()=delete
No default constructor.
bool backProjectHomogeneousBatch(const Eigen::Matrix2Xd &imagePoints, Eigen::Matrix4Xd *directions, std::vector< bool > *success) const
Back-project 2d image points into homogeneous points (direction vectors).
Definition: PinholeCamera.hpp:528
double fu_
focalLengthU
Definition: PinholeCamera.hpp:319
double one_over_fu_
1.0 / fu_
Definition: PinholeCamera.hpp:323
double fv_
focalLengthV
Definition: PinholeCamera.hpp:320
double fu_over_fv_
fu_ / fv_
Definition: PinholeCamera.hpp:325
bool isInImage(const Eigen::Vector2d &imagePoint) const
Check if the keypoint is in the image.
Definition: CameraBase.hpp:95
CameraBase::ProjectionStatus project(const Eigen::Vector3d &point, Eigen::Vector2d *imagePoint) const
Projects a Euclidean point to a 2d image point (projection). Uses projection including distortion mod...
Definition: PinholeCamera.hpp:109
Eigen::Matrix< double, NumIntrinsics, 1 > intrinsics_
summary of all intrinsics parameters
Definition: PinholeCamera.hpp:318
bool backProjectHomogeneous(const Eigen::Vector2d &imagePoint, Eigen::Vector4d *direction) const
Back-project a 2d image point into homogeneous point (direction vector).
Definition: PinholeCamera.hpp:500
CameraBase::ProjectionStatus projectWithExternalParameters(const Eigen::Vector3d &point, const Eigen::VectorXd &parameters, Eigen::Vector2d *imagePoint, Eigen::Matrix< double, 2, 3 > *pointJacobian, Eigen::Matrix2Xd *intrinsicsJacobian=NULL) const
Projects a Euclidean point to a 2d image point (projection). Uses projection including distortion mod...
Definition: PinholeCamera.hpp:230
bool backProjectBatch(const Eigen::Matrix2Xd &imagePoints, Eigen::Matrix3Xd *directions, std::vector< bool > *success) const
Back-project 2d image points into Euclidean space (direction vectors).
Definition: PinholeCamera.hpp:481
CameraBase::ProjectionStatus projectHomogeneousWithExternalParameters(const Eigen::Vector4d &point, const Eigen::VectorXd &parameters, Eigen::Vector2d *imagePoint, Eigen::Matrix< double, 2, 4 > *pointJacobian=NULL, Eigen::Matrix2Xd *intrinsicsJacobian=NULL) const
Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection includin...
Definition: PinholeCamera.hpp:382
bool backProject(const Eigen::Vector2d &imagePoint, Eigen::Vector3d *direction) const
Back-project a 2d image point into Euclidean space (direction vector).
Definition: PinholeCamera.hpp:426
double cu_
imageCenterU
Definition: PinholeCamera.hpp:321
void projectBatch(const Eigen::Matrix3Xd &points, Eigen::Matrix2Xd *imagePoints, std::vector< CameraBase::ProjectionStatus > *stati) const
Projects Euclidean points to 2d image points (projection) in a batch. Uses projection including disto...
Definition: PinholeCamera.hpp:328
bool setIntrinsics(const Eigen::VectorXd &intrinsics)
overwrite all intrinsics - use with caution !
Definition: PinholeCamera.hpp:74
CameraBase::ProjectionStatus projectHomogeneous(const Eigen::Vector4d &point, Eigen::Vector2d *imagePoint) const
Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection includin...
Definition: PinholeCamera.hpp:345
bool isMasked(const Eigen::Vector2d &imagePoint) const
Check if the keypoint is masked.
Definition: CameraBase.hpp:83
void projectHomogeneousBatch(const Eigen::Matrix4Xd &points, Eigen::Matrix2Xd *imagePoints, std::vector< CameraBase::ProjectionStatus > *stati) const
Projects points in homogenous coordinates to 2d image points (projection) in a batch. Uses projection including distortion models.
Definition: PinholeCamera.hpp:406
double one_over_fv_
1.0 / fv_
Definition: PinholeCamera.hpp:324
Base class for all camera models.
Definition: CameraBase.hpp:60
void getIntrinsics(Eigen::VectorXd &intrinsics) const
Get the intrinsics as a concatenated vector.
Definition: PinholeCamera.hpp:94
double cv_
imageCenterV
Definition: PinholeCamera.hpp:322