Class Extrinsics
- Defined in File extrinsics.hpp 
Class Documentation
- 
class Extrinsics
- This class implements the extrinsic transformation of a camera, which comprises a rotation and translation and thus have 6 degrees if freedom. - Most literature describe the extrinsic parameters as a combination of a \(3\times 3\) rotation matrix and a three-dimenstional translation vector. However, this representation is ambiguous with respect to the coordinate system in which the extrisic parameters are described. In the following it is described how the different parameters are interpreted in the scope of lib3D: - In the scope of lib3D, the roational part of the extrinsic camera parameters are interpreted as the orientation of the new coordinate system with respect to a reference system. This means that the column vectors \(\mathrm{r}_x, \mathrm{r}_y \text{and} \mathrm{r}_z\) of the rotation matrix \(\mathrm{\mathbf{R}}\) describe the direction of the different coordinate axes belonging to the euclidean coordiante system of the camera: \[ \mathrm{\mathbf{R}} = \begin{pmatrix} \mathrm{r}_x, \mathrm{r}_y , \mathrm{r}_z \end{pmatrix} \]In the local coordiante system of the camera, the z-axis point in the viewing direction, the x-axis to the right and the y-axis downwards. Appart from the rotation matrix, the camera rotation can also be accessed and set by a rodrigues vector which, consequently, is also interpreted as the rotation of the camera coordinate sytem with respect to the reference system.- The three-dimensional translation of the camera can either be accessed by the vector \(\mathrm{C}\) or by the vector \(\mathrm{t}\). While \(\mathrm{C}\) describes the absolute position of the camera center with respect to the reference system, the vector \(\mathrm{t} = - \mathrm{\mathbf{R}^T} \cdot \mathrm{C}\) describes the origin of the reference system as seen by the camera. Thus, when the rotation of the camera is updated, \(\mathrm{t}\) is also recalculated. - Extrinsic Transformation - In summary there are two transformations that are described by the camera extrinsic parameters, namely: - \(\mathrm{\mathbf{T}_{local\,\rightarrow\,ref}} = \begin{bmatrix} \mathrm{\mathbf{R}} & \mathrm{C} \\ \mathrm{0} & \mathrm{1} \end{bmatrix} \) which will transform a point \(\mathrm{P}_\mathrm{loc}\) from the local coordinate system of the camera to the reference system and, 
- \(\mathrm{\mathbf{T}_{ref\,\rightarrow\,local}} = \mathrm{\mathbf{T}_{local\,\rightarrow\,ref}}^{-1} = \begin{bmatrix} \mathbf{R}^\mathrm{T} & -\mathbf{R}^\mathrm{T} \mathrm{C} \\ 0 & 1 \end{bmatrix} = \begin{bmatrix} \mathbf{R}^\mathrm{T} & \mathrm{t} \\ 0 & 1 \end{bmatrix} \) which will transform a point \(\mathrm{P}_\mathrm{ref}\) given in the reference coordiante system to the local camera coordinate system. 
 - NOTE: The notation above differes from the notation as describen in OpenCV in the notation of \(\mathrm{\mathbf{R}}\). What OpenCV denotes as \(\mathrm{\mathbf{R}}\) corresponds to \(\mathbf{R}^\mathrm{T}\) in the notation above. - lib3d::Extrinisics hold a memeber variable which stores the direction in which the extrinsic transformation points and this how the values stored in the rotation ant translation are to be interpreted. - Public Types - 
enum ETransfDirection
- Enumeration holding direction of transfomration which is represented by the Extrinsic transformation. - Values: - 
enumerator REF_2_LOCAL
- Transforming a point \(\mathrm{P}_\mathrm{ref}\) given in a reference coordiante system to the local camera coordinate system. 
 - 
enumerator LOCAL_2_REF
- Transforming a point \(\mathrm{P}_\mathrm{loc}\) given in the local camera coordiante system to a reference system. 
 
- 
enumerator REF_2_LOCAL
 - Public Functions - 
inline explicit Extrinsics()
- Default (zero initialization) constructor. This will initialize direction of the extrinsic transformation with lib3d::Extrinsics::REF_2_LOCAL. 
 - 
inline explicit Extrinsics(const ETransfDirection transfDirection)
- Initialization constructor, intializing the direction with the given variable. 
 - 
inline explicit Extrinsics(const cv::Matx33d &RMat, const cv::Vec3d &TVec, const ETransfDirection transfDirection = REF_2_LOCAL)
- Initialization constructor, initializing the extrinsic camera parameters by providing a rotation matrix and a translation vector. The interpretation of the given values is provided by the given transformation direction. 
 - 
inline explicit Extrinsics(const cv::Vec3d &rodriguesVec, const cv::Vec3d &TVec, const ETransfDirection transfDirection = REF_2_LOCAL)
- Initialization constructor, initializing the extrinsic camera parameters by providing a rodrigues vector and a translation vector. The interpretation of the given values is provided by the given transformation direction. 
 - 
inline explicit Extrinsics(const cv::Mat &RMatOrVec, const cv::Mat &TVec, const ETransfDirection transfDirection = REF_2_LOCAL)
- Initialization constructor, initializing the extrinsic camera parameters by providing a rotation and a translation vector. The rotaton can be given as a matrix or a vector. The interpretation of the given values is provided by the given transformation direction. 
 - 
inline explicit Extrinsics(const cv::Matx44d &RTMat, const ETransfDirection transfDirection = REF_2_LOCAL)
- Initialization constructor, initializing the extrinsic camera parameters by providing a \(4\times4\) transformation matrix. The interpretation of the given values is provided by the given transformation direction. 
 - 
inline explicit Extrinsics(const cv::Mat &RTMat, const ETransfDirection transfDirection = REF_2_LOCAL)
- Initialization constructor, initializing the extrinsic camera parameters by providing a \(4\times4\) transformation matrix. The interpretation of the given values is provided by the given transformation direction. 
 - 
inline Extrinsics(const Extrinsics &rhs)
- Copy constructor. 
 - 
inline Extrinsics(Extrinsics &&rhs)
- Move constructor. 
 - 
inline Extrinsics &operator=(const Extrinsics &rhs)
- Copy assignment operator. 
 - 
inline Extrinsics &operator=(Extrinsics &&rhs)
- Move assignment operator. 
 - 
inline bool operator==(const Extrinsics &rhs)
- Comparison operator. - Returns:
- True, if both rotation and translation of the two objects are equal. 
 
 - 
inline bool operator!=(const Extrinsics &rhs)
- Comparison operator. - Returns:
- True, if both rotation and translation of the two objects are NOT the same. 
 
 - 
inline Extrinsics getInverse() const
- Method to get Extrinsics object that represents the inverse transformation. 
 - 
inline cv::Matx44d getRTMatrix() const
- Get the \(4\times 4\) extrinsic transformation matrix. The direction of transformation is determined by the member variable mTransfDirection. 
 - 
inline cv::Matx44d getRTMatrix(const ETransfDirection &transfDirection) const
- Get the \(4\times 4\) extrinsic transformation matrix. The direction of transformation is determined either by the member variable mTransfDirection or by the povided input variable transfDirection. 
 - 
inline cv::Matx33d getRotationMat() const
- Get the \(3\times 3\) rotation matrix. The direction of transformation is determined by the member variable mTransfDirection. 
 - 
inline cv::Vec3d getRotationVec() const
- Get the three dimensional rotational rodrigues vector. The direction of transformation is determined by the member variable mTransfDirection. 
 - 
inline cv::Vec3d getTranslationVec() const
- Get the three dimensional translation vector. The direction of transformation is determined by the member variable mTransfDirection. 
 - 
inline void setExtrinsics(cv::Matx33d rotMat, cv::Vec3d translVec)
- Method to set extrinsics by providing a \(3\times 3\) rotation matrix and a three dimensional translation vector. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setExtrinsics(cv::Vec3d rotVec, cv::Vec3d translVec)
- Method to set extrinsics by providing a three dimensional rotation vector and a three dimensional translation vector. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setRTMatrix(const cv::Matx44d &RTMat)
- Set the extrinsic camera pose by a \(4\times 4\) transformation matrix. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setRTMatrix(const cv::Mat &RTMat)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
inline void setRTMatrix(const cv::Matx44d &RTMat, const ETransfDirection &transfDirection)
- Set the extrinsic camera pose by a \(4\times 4\) transformation matrix. The interpretation of the given variables is determined either by the member variable mTransfDirection or by the povided input variable transfDirection. 
 - 
inline void setRTMatrix(const cv::Mat &RTMat, const ETransfDirection &transfDirection)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
inline void setRotationMat(const cv::Matx33d &RMat)
- Method to set rotational part by providing a \(3\times 3\) rotation matrix. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setRotationVec(const cv::Vec3d &RodriguesVec)
- Method to set rotational part by providing a three dimensional rodrigues vector. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setRotationMatOrVec(const cv::Mat &rotationMatOrVec)
- Method to set rotational part by providing a \(3\times 3\) rotation matrix or a three dimensional rodrigues vector. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setTranslationVec(const cv::Vec3d &TVec)
- Method to set translational part by providing a three dimensional translation vector. The interpretation of the given variables is determined by the member variable mTransfDirection. 
 - 
inline void setTranslationVec(const cv::Mat &TVec)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
inline void setTranslationVec(const double &x, const double &y, const double &z)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
inline ETransfDirection getTransfDirection() const
- Returns the direction of transformation of the Extrinsics. 
 - 
inline void setTransfDirection(const ETransfDirection &transfDirection)
- Method to set the direction of transformation of the Extrinsics. This will invert the transformation if data is already set and the passed direction differes from the one stored. 
 - Public Members - 
Translation translation
- Translational part of the extrinsic camera parameters. 
 - Public Static Functions - 
static inline void composeRTMatrix(const cv::Matx33d &rotMat, const cv::Vec3d &translVec, cv::Matx44d &RTMat)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
static inline cv::Matx44d composeRTMatrix(const cv::Matx33d &rotMat, const cv::Vec3d &translVec)
- Function to compose \(4\times 4\) transformation matrix from rotation and translation. - Parameters:
- rotMat – [in] \(3\times 3\) rotation matrix \(\mathrm{\mathbf{R}}\) 
- translVec – [in] three-dimensional translation vector \(\mathrm{t}\) 
 
- Returns:
- \(4\times 4\) transformation matrix \(\mathrm{\mathbf{T}} = \begin{bmatrix} \mathrm{\mathbf{R}} & \mathrm{t} \\ \mathrm{0} & \mathrm{1} \end{bmatrix} \) 
 
 - 
static inline cv::Matx44d composeRTMatrix(const cv::Vec3d &rotVec, const cv::Vec3d &translVec)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
static inline void composeRTMatrix(const cv::Vec3d &rotVec, const cv::Vec3d &translVec, cv::Matx44d &RTMat)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
static inline void decomposeRTMatrix(const cv::Matx44d &RTMat, cv::Matx33d &rotMat, cv::Vec3d &translVec)
- Function to decompose \(4\times 4\) transformation matrix into rotation and translation. - Parameters:
- RTMat – [in] \(4\times 4\) transformation matrix \(\mathrm{\mathbf{T}} = \begin{bmatrix} \mathrm{\mathbf{R}} & \mathrm{t} \\ \mathrm{0} & \mathrm{1} \end{bmatrix} \) 
- rotMat – [out] \(3\times 3\) rotation matrix \(\mathrm{\mathbf{R}}\) 
- translVec – [out] three-dimensional translation vector \(\mathrm{t}\) 
 
 
 - 
static inline void decomposeRTMatrix(const cv::Matx44d &RTMat, cv::Vec3d &rotVec, cv::Vec3d &translVec)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
static inline cv::Matx44d computeRelativeExtrinsics(const cv::Matx44d &eSrc, const cv::Matx44d &eDst)
- Function to compute relative extrinsic transformation between two Extrinsics. - Parameters:
- eSrc – [in] Source Extrinsics given as RT Matrix 
- eDst – [in] Destination Extrinsics given as RT Matrix 
 
- Returns:
- Relative RT matrix going from eSrc to eDst. 
 
 - 
static inline cv::Mat computeRelativeExtrinsics(const cv::Mat &eSrc, const cv::Mat &eDst)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. 
 - 
static inline Extrinsics computeRelativeExtrinsics(const Extrinsics &eSrc, const Extrinsics &eDst)
- This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts. - Note - This will transform the source and destination extrinsics into Extrinsics::REF_2_LOCAL before computing the transformation. - Parameters:
- eSrc – [in] Source Extrinsics 
- eDst – [in] Destination Extrinsics 
 
- Returns:
- Relative Extrinsic going from eSrc to eDst. 
 
 - 
static inline void computeHomePose(Extrinsics ptPose, double pan, double tilt, Extrinsics &outHomePose)
- Function to compute HomePose (for which pan=tilt=0) from given Pan-Tilt pose using supplied pan and tilt values. 
 - 
static inline void computePanTiltPose(Extrinsics homePose, double pan, double tilt, Extrinsics &outPTPose)
- Function to compute shifted Pan-Tilt-Pose with the given values for the given Home-/Zero-Pose.