ov_core::FeatureInitializer::ClonePose struct

Structure which stores pose estimates for use in triangulation.

  • R_GtoC - rotation from global to camera
  • p_CinG - position of camera in global frame

Constructors, destructors, conversion operators

ClonePose(Eigen::Matrix<double, 3, 3> R, Eigen::Matrix<double, 3, 1> p)
Constructs pose from rotation and position.
ClonePose(Eigen::Matrix<double, 4, 1> q, Eigen::Matrix<double, 3, 1> p)
Constructs pose from quaternion and position.
ClonePose()
Default constructor.

Public functions

auto Rot() -> Eigen::Matrix<double, 3, 3>&
Accessor for rotation.
auto pos() -> Eigen::Matrix<double, 3, 1>&
Accessor for position.

Public variables

Eigen::Matrix<double, 3, 3> _Rot
Rotation.
Eigen::Matrix<double, 3, 1> _pos
Position.