OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
okvis::cameras::PinholeCamera< DISTORTION_T > Class Template Reference

#include <PinholeCamera.hpp>

Inheritance diagram for okvis::cameras::PinholeCamera< DISTORTION_T >:
okvis::cameras::CameraBase

Public Member Functions

 PinholeCamera (int imageWidth, int imageHeight, double focalLengthU, double focalLengthV, double imageCenterU, double imageCenterV, const distortion_t &distortion, uint64_t id=-1)
 Constructor that will figure out the type of distortion. More...
 
 ~PinholeCamera ()
 Destructor. More...
 
double focalLengthU () const
 Get the focal length along the u-dimension. More...
 
double focalLengthV () const
 Get the focal length along the v-dimension. More...
 
double imageCenterU () const
 Get the image centre along the u-dimension. More...
 
double imageCenterV () const
 Get the focal image centre along the v-dimension. More...
 
void getIntrinsics (Eigen::VectorXd &intrinsics) const
 Get the intrinsics as a concatenated vector. More...
 
bool setIntrinsics (const Eigen::VectorXd &intrinsics)
 overwrite all intrinsics - use with caution ! More...
 
int noIntrinsicsParameters () const
 Get the total number of intrinsics. More...
 
std::string type () const
 Obtain the projection type. More...
 
const std::string distortionType () const
 Obtain the projection type. More...
 
Methods to project points
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 models. More...
 
CameraBase::ProjectionStatus project (const Eigen::Vector3d &point, 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 models. More...
 
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 models. More...
 
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 distortion models. More...
 
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 including distortion models. More...
 
CameraBase::ProjectionStatus projectHomogeneous (const Eigen::Vector4d &point, Eigen::Vector2d *imagePoint, Eigen::Matrix< double, 2, 4 > *pointJacobian, Eigen::Matrix2Xd *intrinsicsJacobian=NULL) const
 Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection including distortion models. More...
 
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 including distortion models. More...
 
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. More...
 
Methods to backproject points
bool backProject (const Eigen::Vector2d &imagePoint, Eigen::Vector3d *direction) const
 Back-project a 2d image point into Euclidean space (direction vector). More...
 
bool backProject (const Eigen::Vector2d &imagePoint, Eigen::Vector3d *direction, Eigen::Matrix< double, 3, 2 > *pointJacobian) const
 Back-project a 2d image point into Euclidean space (direction vector). More...
 
bool backProjectBatch (const Eigen::Matrix2Xd &imagePoints, Eigen::Matrix3Xd *directions, std::vector< bool > *success) const
 Back-project 2d image points into Euclidean space (direction vectors). More...
 
bool backProjectHomogeneous (const Eigen::Vector2d &imagePoint, Eigen::Vector4d *direction) const
 Back-project a 2d image point into homogeneous point (direction vector). More...
 
bool backProjectHomogeneous (const Eigen::Vector2d &imagePoint, Eigen::Vector4d *direction, Eigen::Matrix< double, 4, 2 > *pointJacobian) const
 Back-project a 2d image point into homogeneous point (direction vector). More...
 
bool backProjectHomogeneousBatch (const Eigen::Matrix2Xd &imagePoints, Eigen::Matrix4Xd *directions, std::vector< bool > *success) const
 Back-project 2d image points into homogeneous points (direction vectors). More...
 
- Public Member Functions inherited from okvis::cameras::CameraBase
 CameraBase ()
 default Constructor – does nothing serious More...
 
 CameraBase (int imageWidth, int imageHeight, uint64_t id=0)
 Constructor for width, height and Id. More...
 
virtual ~CameraBase ()
 Destructor – does nothing. More...
 
uint32_t imageWidth () const
 The width of the image in pixels. More...
 
uint32_t imageHeight () const
 The height of the image in pixels. More...
 
bool setMask (const cv::Mat &mask)
 Set the mask. It must be the same size as the image and comply with OpenCV: 0 == masked, nonzero == valid. Type must be CV_8U1C. More...
 
bool hasMask () const
 Was a nonzero mask set? More...
 
bool removeMask ()
 stop masking More...
 
const cv::Mat & mask () const
 Get the mask. More...
 
void setId (uint64_t id)
 Set an Id. More...
 
uint64_t id () const
 Obtain the Id. More...
 
virtual void projectBatch (const Eigen::Matrix3Xd &points, Eigen::Matrix2Xd *imagePoints, std::vector< ProjectionStatus > *stati) const =0
 Projects Euclidean points to 2d image points (projection) in a batch. Uses projection including distortion models. More...
 
virtual void projectHomogeneousBatch (const Eigen::Matrix4Xd &points, Eigen::Matrix2Xd *imagePoints, std::vector< ProjectionStatus > *stati) const =0
 Projects points in homogenous coordinates to 2d image points (projection) in a batch. Uses projection including distortion models. More...
 
virtual Eigen::Vector2d createRandomImagePoint () const
 Creates a random (uniform distribution) image point. More...
 
virtual Eigen::Vector3d createRandomVisiblePoint (double minDist=0.0, double maxDist=10.0) const
 Creates a random visible point in Euclidean coordinates. More...
 
virtual Eigen::Vector4d createRandomVisibleHomogeneousPoint (double minDist=0.0, double maxDist=10.0) const
 Creates a random visible point in homogeneous coordinates. More...
 

Static Public Member Functions

static std::shared_ptr
< CameraBase
createTestObject ()
 get a test instance More...
 
static PinholeCamera testObject ()
 get a test instance More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef DISTORTION_T 
distortion_t
 Makes the distortion type accessible. More...
 

Static Public Attributes

static const int NumProjectionIntrinsics = 4
 optimisable projection intrinsics More...
 
static const int NumIntrinsics
 total number of intrinsics More...
 

Protected Member Functions

 PinholeCamera ()=delete
 No default constructor. More...
 
- Protected Member Functions inherited from okvis::cameras::CameraBase
bool isMasked (const Eigen::Vector2d &imagePoint) const
 Check if the keypoint is masked. More...
 
bool isInImage (const Eigen::Vector2d &imagePoint) const
 Check if the keypoint is in the image. More...
 

Protected Attributes

distortion_t distortion_
 the distortion to be used More...
 
Eigen::Matrix< double,
NumIntrinsics, 1 > 
intrinsics_
 summary of all intrinsics parameters More...
 
double fu_
 focalLengthU More...
 
double fv_
 focalLengthV More...
 
double cu_
 imageCenterU More...
 
double cv_
 imageCenterV More...
 
double one_over_fu_
 1.0 / fu_ More...
 
double one_over_fv_
 1.0 / fv_ More...
 
double fu_over_fv_
 fu_ / fv_ More...
 
- Protected Attributes inherited from okvis::cameras::CameraBase
cv::Mat mask_
 The mask – empty by default. More...
 
int imageWidth_
 image width in pixels More...
 
int imageHeight_
 image height in pixels More...
 
uint64_t id_
 an Id More...
 

Additional Inherited Members

- Public Types inherited from okvis::cameras::CameraBase
enum  ProjectionStatus {
  ProjectionStatus::Successful, ProjectionStatus::OutsideImage, ProjectionStatus::Masked, ProjectionStatus::Behind,
  ProjectionStatus::Invalid
}
 

Constructor & Destructor Documentation

template<class DISTORTION_T >
okvis::cameras::PinholeCamera< DISTORTION_T >::PinholeCamera ( int  imageWidth,
int  imageHeight,
double  focalLengthU,
double  focalLengthV,
double  imageCenterU,
double  imageCenterV,
const distortion_t distortion,
uint64_t  id = -1 
)

Constructor that will figure out the type of distortion.

Parameters
[in]imageWidthThe width in pixels.
[in]imageHeightThe height in pixels.
[in]focalLengthUThe horizontal focal length in pixels.
[in]focalLengthVThe vertical focal length in pixels.
[in]imageCenterUThe horizontal centre in pixels.
[in]imageCenterVThe vertical centre in pixels.
[in]distortionThe distortion object to be used.
[in]idAssign a generic ID, if desired.
template<class DISTORTION_T >
okvis::cameras::PinholeCamera< DISTORTION_T >::~PinholeCamera ( )
inline

Destructor.

template<class DISTORTION_T >
okvis::cameras::PinholeCamera< DISTORTION_T >::PinholeCamera ( )
protecteddelete

No default constructor.

Member Function Documentation

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProject ( const Eigen::Vector2d &  imagePoint,
Eigen::Vector3d *  direction 
) const
inlinevirtual

Back-project a 2d image point into Euclidean space (direction vector).

Parameters
[in]imagePointThe image point.
[out]directionThe Euclidean direction vector.
Returns
true on success.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProject ( const Eigen::Vector2d &  imagePoint,
Eigen::Vector3d *  direction,
Eigen::Matrix< double, 3, 2 > *  pointJacobian 
) const
inlinevirtual

Back-project a 2d image point into Euclidean space (direction vector).

Parameters
[in]imagePointThe image point.
[out]directionThe Euclidean direction vector.
[out]pointJacobianJacobian of the back-projection function w.r.t. the point.
Returns
true on success.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProjectBatch ( const Eigen::Matrix2Xd &  imagePoints,
Eigen::Matrix3Xd *  directions,
std::vector< bool > *  success 
) const
inlinevirtual

Back-project 2d image points into Euclidean space (direction vectors).

Parameters
[in]imagePointsThe image points (one point per column).
[out]directionsThe Euclidean direction vectors (one point per column).
[out]successSuccess of each of the back-projection

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProjectHomogeneous ( const Eigen::Vector2d &  imagePoint,
Eigen::Vector4d *  direction 
) const
inlinevirtual

Back-project a 2d image point into homogeneous point (direction vector).

Parameters
[in]imagePointThe image point.
[out]directionThe homogeneous point as direction vector.
Returns
true on success.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProjectHomogeneous ( const Eigen::Vector2d &  imagePoint,
Eigen::Vector4d *  direction,
Eigen::Matrix< double, 4, 2 > *  pointJacobian 
) const
inlinevirtual

Back-project a 2d image point into homogeneous point (direction vector).

Parameters
[in]imagePointThe image point.
[out]directionThe homogeneous point as direction vector.
[out]pointJacobianJacobian of the back-projection function.
Returns
true on success.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::backProjectHomogeneousBatch ( const Eigen::Matrix2Xd &  imagePoints,
Eigen::Matrix4Xd *  directions,
std::vector< bool > *  success 
) const
inlinevirtual

Back-project 2d image points into homogeneous points (direction vectors).

Parameters
[in]imagePointsThe image points (one point per column).
[out]directionsThe homogeneous points as direction vectors (one point per column).
[out]successSuccess of each of the back-projection

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
static std::shared_ptr<CameraBase> okvis::cameras::PinholeCamera< DISTORTION_T >::createTestObject ( )
inlinestatic

get a test instance

template<class DISTORTION_T >
const std::string okvis::cameras::PinholeCamera< DISTORTION_T >::distortionType ( ) const
inlinevirtual

Obtain the projection type.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::focalLengthU ( ) const
inline

Get the focal length along the u-dimension.

Returns
The horizontal focal length in pixels.
template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::focalLengthV ( ) const
inline

Get the focal length along the v-dimension.

Returns
The vertical focal length in pixels.
template<class DISTORTION_T >
void okvis::cameras::PinholeCamera< DISTORTION_T >::getIntrinsics ( Eigen::VectorXd &  intrinsics) const
inlinevirtual

Get the intrinsics as a concatenated vector.

Returns
The intrinsics as a concatenated vector.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::imageCenterU ( ) const
inline

Get the image centre along the u-dimension.

Returns
The horizontal centre in pixels.
template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::imageCenterV ( ) const
inline

Get the focal image centre along the v-dimension.

Returns
The vertical centre in pixels.
template<class DISTORTION_T >
int okvis::cameras::PinholeCamera< DISTORTION_T >::noIntrinsicsParameters ( ) const
inlinevirtual

Get the total number of intrinsics.

Returns
Number of intrinsics parameters.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::project ( const Eigen::Vector3d &  point,
Eigen::Vector2d *  imagePoint 
) const
inlinevirtual

Projects a Euclidean point to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Euclidean coordinates.
[out]imagePointThe image point.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::project ( const Eigen::Vector3d &  point,
Eigen::Vector2d *  imagePoint,
Eigen::Matrix< double, 2, 3 > *  pointJacobian,
Eigen::Matrix2Xd *  intrinsicsJacobian = NULL 
) const
inlinevirtual

Projects a Euclidean point to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Euclidean coordinates.
[out]imagePointThe image point.
[out]pointJacobianThe Jacobian of the projection function w.r.t. the point..
[out]intrinsicsJacobianThe Jacobian of the projection function w.r.t. the intinsics.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
void okvis::cameras::PinholeCamera< DISTORTION_T >::projectBatch ( const Eigen::Matrix3Xd &  points,
Eigen::Matrix2Xd *  imagePoints,
std::vector< CameraBase::ProjectionStatus > *  stati 
) const
inline

Projects Euclidean points to 2d image points (projection) in a batch. Uses projection including distortion models.

Parameters
[in]pointsThe points in Euclidean coordinates (one point per column).
[out]imagePointsThe image points (one point per column).
[out]statiGet information about the success of the projections. See ProjectionStatus for more information.
template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::projectHomogeneous ( const Eigen::Vector4d &  point,
Eigen::Vector2d *  imagePoint 
) const
inlinevirtual

Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Homogeneous coordinates.
[out]imagePointThe image point.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::projectHomogeneous ( const Eigen::Vector4d &  point,
Eigen::Vector2d *  imagePoint,
Eigen::Matrix< double, 2, 4 > *  pointJacobian,
Eigen::Matrix2Xd *  intrinsicsJacobian = NULL 
) const
inlinevirtual

Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Homogeneous coordinates.
[out]imagePointThe image point.
[out]pointJacobianThe Jacobian of the projection function w.r.t. the point.
[out]intrinsicsJacobianThe Jacobian of the projection function w.r.t. the intrinsics.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
void okvis::cameras::PinholeCamera< DISTORTION_T >::projectHomogeneousBatch ( const Eigen::Matrix4Xd &  points,
Eigen::Matrix2Xd *  imagePoints,
std::vector< CameraBase::ProjectionStatus > *  stati 
) const
inline

Projects points in homogenous coordinates to 2d image points (projection) in a batch. Uses projection including distortion models.

Parameters
[in]pointsThe points in homogeneous coordinates (one point per column).
[out]imagePointsThe image points (one point per column).
[out]statiGet information about the success of the projections. See ProjectionStatus for more information.
template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::projectHomogeneousWithExternalParameters ( const Eigen::Vector4d &  point,
const Eigen::VectorXd &  parameters,
Eigen::Vector2d *  imagePoint,
Eigen::Matrix< double, 2, 4 > *  pointJacobian = NULL,
Eigen::Matrix2Xd *  intrinsicsJacobian = NULL 
) const
inlinevirtual

Projects a point in homogenous coordinates to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Homogeneous coordinates.
[in]parametersThe intrinsics.
[out]imagePointThe image point.
[out]pointJacobianThe Jacobian of the projection function w.r.t. the point.
[out]intrinsicsJacobianThe Jacobian of the projection function w.r.t. the intrinsics.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
CameraBase::ProjectionStatus okvis::cameras::PinholeCamera< DISTORTION_T >::projectWithExternalParameters ( const Eigen::Vector3d &  point,
const Eigen::VectorXd &  parameters,
Eigen::Vector2d *  imagePoint,
Eigen::Matrix< double, 2, 3 > *  pointJacobian,
Eigen::Matrix2Xd *  intrinsicsJacobian = NULL 
) const
inlinevirtual

Projects a Euclidean point to a 2d image point (projection). Uses projection including distortion models.

Parameters
[in]pointThe point in Euclidean coordinates.
[in]parametersThe intrinsics.
[out]imagePointThe image point.
[out]pointJacobianThe Jacobian of the projection function w.r.t. the point..
[out]intrinsicsJacobianThe Jacobian of the projection function w.r.t. the intinsics.
Returns
Get information about the success of the projection. See ProjectionStatus for more information.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
bool okvis::cameras::PinholeCamera< DISTORTION_T >::setIntrinsics ( const Eigen::VectorXd &  intrinsics)
inlinevirtual

overwrite all intrinsics - use with caution !

Parameters
[in]intrinsicsThe intrinsics as a concatenated vector.

Implements okvis::cameras::CameraBase.

template<class DISTORTION_T >
static PinholeCamera okvis::cameras::PinholeCamera< DISTORTION_T >::testObject ( )
inlinestatic

get a test instance

template<class DISTORTION_T >
std::string okvis::cameras::PinholeCamera< DISTORTION_T >::type ( ) const
inlinevirtual

Obtain the projection type.

Implements okvis::cameras::CameraBase.

Member Data Documentation

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::cu_
protected

imageCenterU

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::cv_
protected

imageCenterV

template<class DISTORTION_T >
distortion_t okvis::cameras::PinholeCamera< DISTORTION_T >::distortion_
protected

the distortion to be used

template<class DISTORTION_T >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef DISTORTION_T okvis::cameras::PinholeCamera< DISTORTION_T >::distortion_t

Makes the distortion type accessible.

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::fu_
protected

focalLengthU

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::fu_over_fv_
protected

fu_ / fv_

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::fv_
protected

focalLengthV

template<class DISTORTION_T >
Eigen::Matrix<double, NumIntrinsics, 1> okvis::cameras::PinholeCamera< DISTORTION_T >::intrinsics_
protected

summary of all intrinsics parameters

template<class DISTORTION_T >
const int okvis::cameras::PinholeCamera< DISTORTION_T >::NumIntrinsics
static
Initial value:
+ distortion_t::NumDistortionIntrinsics

total number of intrinsics

template<class DISTORTION_T >
const int okvis::cameras::PinholeCamera< DISTORTION_T >::NumProjectionIntrinsics = 4
static

optimisable projection intrinsics

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::one_over_fu_
protected

1.0 / fu_

template<class DISTORTION_T >
double okvis::cameras::PinholeCamera< DISTORTION_T >::one_over_fv_
protected

1.0 / fv_


The documentation for this class was generated from the following file: