Calibration Library 1.0.0
A C++ library for camera calibration and vision-related geometric transformations
Loading...
Searching...
No Matches
calib::PoseFromHResult Struct Referencefinal

Recover target->camera pose (R,t) from camera matrix K and planar homography H. More...

#include <posefromhomography.h>

Collaboration diagram for calib::PoseFromHResult:

Public Attributes

bool success {false}
 
Eigen::Isometry3d c_se3_t = Eigen::Isometry3d::Identity()
 
double scale {1.0}
 
double cond_check {1.0}
 
std::string message
 

Detailed Description

Recover target->camera pose (R,t) from camera matrix K and planar homography H.

Assumptions:

  • H maps target planar homogeneous coords (X,Y,1) to pixel coords (u,v,1).
  • Distortion is negligible (or already compensated).
  • K is well-conditioned (fx, fy > 0).

Steps: 1) Hn = K^{-1} H 2) scale s = 1 / mean(||Hn.col(0)||, ||Hn.col(1)||) 3) r1 = s * Hn.col(0), r2 = s * Hn.col(1), t = s * Hn.col(2) 4) r3 = r1 x r2; R_pre = [r1 r2 r3] 5) Orthonormalize R via SVD (polar decomposition): R = U V^T (det>0) 6) Enforce positive forward direction (t_z > 0); if not, flip R,t

Definition at line 32 of file posefromhomography.h.

Member Data Documentation

◆ c_se3_t

Eigen::Isometry3d calib::PoseFromHResult::c_se3_t = Eigen::Isometry3d::Identity()

Definition at line 34 of file posefromhomography.h.

◆ cond_check

double calib::PoseFromHResult::cond_check {1.0}

Definition at line 36 of file posefromhomography.h.

◆ message

std::string calib::PoseFromHResult::message

Definition at line 37 of file posefromhomography.h.

◆ scale

double calib::PoseFromHResult::scale {1.0}

Definition at line 35 of file posefromhomography.h.

◆ success

bool calib::PoseFromHResult::success {false}

Definition at line 33 of file posefromhomography.h.


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