41 #ifndef INCLUDE_OKVIS_CAMERAS_PINHOLECAMERA_HPP_
42 #define INCLUDE_OKVIS_CAMERAS_PINHOLECAMERA_HPP_
48 #pragma GCC diagnostic push
49 #pragma GCC diagnostic ignored "-Wnon-virtual-dtor"
50 #include <opencv2/core/core.hpp>
51 #pragma GCC diagnostic pop
63 template<
class DISTORTION_T>
67 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
90 + distortion_t::NumDistortionIntrinsics;
122 inline void getIntrinsics(Eigen::VectorXd & intrinsics)
const ;
126 inline bool setIntrinsics(
const Eigen::VectorXd & intrinsics);
146 const Eigen::Vector3d & point, Eigen::Vector2d * imagePoint)
const;
157 const Eigen::Vector3d & point, Eigen::Vector2d * imagePoint,
158 Eigen::Matrix<double, 2, 3> * pointJacobian,
159 Eigen::Matrix2Xd * intrinsicsJacobian = NULL)
const;
171 const Eigen::Vector3d & point,
const Eigen::VectorXd & parameters,
172 Eigen::Vector2d * imagePoint, Eigen::Matrix<double, 2, 3> * pointJacobian,
173 Eigen::Matrix2Xd * intrinsicsJacobian = NULL)
const;
182 const Eigen::Matrix3Xd & points, Eigen::Matrix2Xd * imagePoints,
183 std::vector<CameraBase::ProjectionStatus> * stati)
const;
192 const Eigen::Vector4d & point, Eigen::Vector2d * imagePoint)
const;
203 const Eigen::Vector4d & point, Eigen::Vector2d * imagePoint,
204 Eigen::Matrix<double, 2, 4> * pointJacobian,
205 Eigen::Matrix2Xd * intrinsicsJacobian = NULL)
const;
217 const Eigen::Vector4d & point,
const Eigen::VectorXd & parameters,
218 Eigen::Vector2d * imagePoint,
219 Eigen::Matrix<double, 2, 4> * pointJacobian = NULL,
220 Eigen::Matrix2Xd * intrinsicsJacobian = NULL)
const;
229 const Eigen::Matrix4Xd & points, Eigen::Matrix2Xd * imagePoints,
230 std::vector<CameraBase::ProjectionStatus> * stati)
const;
241 inline bool backProject(
const Eigen::Vector2d & imagePoint,
242 Eigen::Vector3d * direction)
const;
249 inline bool backProject(
const Eigen::Vector2d & imagePoint,
250 Eigen::Vector3d * direction,
251 Eigen::Matrix<double, 3, 2> * pointJacobian)
const;
258 Eigen::Matrix3Xd * directions,
259 std::vector<bool> * success)
const;
266 Eigen::Vector4d * direction)
const;
274 const Eigen::Vector2d & imagePoint, Eigen::Vector4d * direction,
275 Eigen::Matrix<double, 4, 2> * pointJacobian)
const;
282 Eigen::Matrix4Xd * directions,
283 std::vector<bool> * success)
const;
289 return std::shared_ptr<CameraBase>(
new PinholeCamera(752, 480, 350, 360, 378, 238,
290 distortion_t::testObject()));
296 distortion_t::testObject());
302 return "PinholeCamera<" +
distortion_.type() +
">";
static const int NumProjectionIntrinsics
optimisable projection intrinsics
Definition: PinholeCamera.hpp:88
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
Header implementation file for the PinholeCamera class.
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
static const int NumIntrinsics
total number of intrinsics
Definition: PinholeCamera.hpp:89
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
distortion_t distortion_
the distortion to be used
Definition: PinholeCamera.hpp:316
Eigen::Matrix< double, NumIntrinsics, 1 > intrinsics_
summary of all intrinsics parameters
Definition: PinholeCamera.hpp:318
uint32_t imageHeight() const
The height of the image in pixels.
Definition: CameraBase.hpp:143
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 ¶meters, 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
Definition: PinholeCamera.hpp:64
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
double imageCenterU() const
Get the image centre along the u-dimension.
Definition: PinholeCamera.hpp:108
std::string type() const
Obtain the projection type.
Definition: PinholeCamera.hpp:300
CameraBase::ProjectionStatus projectHomogeneousWithExternalParameters(const Eigen::Vector4d &point, const Eigen::VectorXd ¶meters, 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
Header file for the DistortionBase class.
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
uint32_t imageWidth() const
The width of the image in pixels.
Definition: CameraBase.hpp:138
int noIntrinsicsParameters() const
Get the total number of intrinsics.
Definition: PinholeCamera.hpp:130
bool setIntrinsics(const Eigen::VectorXd &intrinsics)
overwrite all intrinsics - use with caution !
Definition: PinholeCamera.hpp:74
double focalLengthU() const
Get the focal length along the u-dimension.
Definition: PinholeCamera.hpp:94
static PinholeCamera testObject()
get a test instance
Definition: PinholeCamera.hpp:293
Header file for the CameraBase class.
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
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef DISTORTION_T distortion_t
Makes the distortion type accessible.
Definition: PinholeCamera.hpp:68
~PinholeCamera()
Destructor.
Definition: PinholeCamera.hpp:84
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
const std::string distortionType() const
Obtain the projection type.
Definition: PinholeCamera.hpp:306
void getIntrinsics(Eigen::VectorXd &intrinsics) const
Get the intrinsics as a concatenated vector.
Definition: PinholeCamera.hpp:94
double focalLengthV() const
Get the focal length along the v-dimension.
Definition: PinholeCamera.hpp:101
double imageCenterV() const
Get the focal image centre along the v-dimension.
Definition: PinholeCamera.hpp:115
static std::shared_ptr< CameraBase > createTestObject()
get a test instance
Definition: PinholeCamera.hpp:287
double cv_
imageCenterV
Definition: PinholeCamera.hpp:322