NDEVR
API Documentation
ImuCamPose

Represents a combined IMU and camera pose for graph optimization. More...

Collaboration diagram for ImuCamPose:
[legend]

Public Member Functions

 ImuCamPose ()
 Default constructor.
 ImuCamPose (Eigen::Matrix3< g_type > &_Rwc, Eigen::Vector3< g_type > &_twc, KeyFrame *pKF)
 Constructs from a rotation, translation, and keyframe.
 ImuCamPose (Frame &pF)
 Constructs from a Frame.
bool isDepthPositive (const Eigen::Vector3< g_type > &Xw, int cam_idx=0) const
 Checks whether a 3D point has positive depth in the given camera.
Eigen::Vector2< g_type > Project (const Eigen::Vector3< g_type > &Xw, int cam_idx=0) const
 Projects a 3D world point to 2D (monocular).
Eigen::Vector3< g_type > ProjectStereo (const Eigen::Vector3< g_type > &Xw, int cam_idx=0) const
 Projects a 3D world point to stereo coordinates.
void SetParam (const Buffer< Eigen::Matrix3< g_type > > &_Rcw, const Buffer< Eigen::Vector3< g_type > > &_tcw, const Buffer< Eigen::Matrix3< g_type > > &_Rbc, const Buffer< Eigen::Vector3< g_type > > &_tbc, const g_type &_bf)
 Sets camera and IMU extrinsic parameters.
void Update (const g_type *pu)
 Updates the pose in the IMU body reference frame.
void UpdateW (const g_type *pu)
 Updates the pose in the world reference frame.

Public Attributes

g_type bf
 Stereo baseline times focal length.
Eigen::Matrix3< g_type > DR
 Delta rotation for 4DoF optimization.
int its
 Iteration counter.
Buffer< GeometricCamera * > pCamera
 Camera models.
Buffer< Eigen::Matrix3< g_type > > Rbc
 Camera-body and body-camera rotations.
Buffer< Eigen::Matrix3< g_type > > Rcw
 Camera-to-world rotations per camera.
Eigen::Matrix3< g_type > Rwb
 IMU body-to-world rotation.
Eigen::Matrix3< g_type > Rwb0
 Initial body-to-world rotation for 4DoF pose graph.
Buffer< Eigen::Vector3< g_type > > tbc
 Camera-body and body-camera translations.
Buffer< Eigen::Vector3< g_type > > tcw
 Camera-to-world translations per camera.
Eigen::Vector3< g_type > twb
 IMU body-to-world translation.

Detailed Description

Represents a combined IMU and camera pose for graph optimization.

Stores the IMU body pose (Rwb, twb) and the derived camera poses for a multi-camera setup, along with extrinsic calibration.

Definition at line 98 of file G2oTypes.h.

Constructor & Destructor Documentation

◆ ImuCamPose() [1/2]

ImuCamPose::ImuCamPose ( Frame & pF)

Constructs from a Frame.

Parameters
[in]pFThe frame to extract pose from.

◆ ImuCamPose() [2/2]

ImuCamPose::ImuCamPose ( Eigen::Matrix3< g_type > & _Rwc,
Eigen::Vector3< g_type > & _twc,
KeyFrame * pKF )

Constructs from a rotation, translation, and keyframe.

Parameters
[in]_RwcWorld-to-camera rotation.
[in]_twcWorld-to-camera translation.
[in]pKFSource keyframe for extrinsics.

Member Function Documentation

◆ isDepthPositive()

bool ImuCamPose::isDepthPositive ( const Eigen::Vector3< g_type > & Xw,
int cam_idx = 0 ) const

Checks whether a 3D point has positive depth in the given camera.

Parameters
[in]Xw3D point in world coordinates.
[in]cam_idxCamera index (default 0).
Returns
True if depth is positive.

◆ Project()

Eigen::Vector2< g_type > ImuCamPose::Project ( const Eigen::Vector3< g_type > & Xw,
int cam_idx = 0 ) const

Projects a 3D world point to 2D (monocular).

Parameters
[in]Xw3D point in world coordinates.
[in]cam_idxCamera index (default 0).
Returns
The 2D projected point.

◆ ProjectStereo()

Eigen::Vector3< g_type > ImuCamPose::ProjectStereo ( const Eigen::Vector3< g_type > & Xw,
int cam_idx = 0 ) const

Projects a 3D world point to stereo coordinates.

Parameters
[in]Xw3D point in world coordinates.
[in]cam_idxCamera index (default 0).
Returns
The 3D stereo projected point (u, v, ur).

◆ SetParam()

void ImuCamPose::SetParam ( const Buffer< Eigen::Matrix3< g_type > > & _Rcw,
const Buffer< Eigen::Vector3< g_type > > & _tcw,
const Buffer< Eigen::Matrix3< g_type > > & _Rbc,
const Buffer< Eigen::Vector3< g_type > > & _tbc,
const g_type & _bf )

Sets camera and IMU extrinsic parameters.

Parameters
[in]_RcwCamera-to-world rotations per camera.
[in]_tcwCamera-to-world translations per camera.
[in]_RbcBody-to-camera rotations.
[in]_tbcBody-to-camera translations.
[in]_bfStereo baseline times focal length.

◆ Update()

void ImuCamPose::Update ( const g_type * pu)

Updates the pose in the IMU body reference frame.

Parameters
[in]puPointer to the 6-element update vector.

◆ UpdateW()

void ImuCamPose::UpdateW ( const g_type * pu)

Updates the pose in the world reference frame.

Parameters
[in]puPointer to the 6-element update vector.

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