![]()  | 
  
    Zivid C++ API 2.10.1+50b274e8-7
    
   Defining the Future of 3D Machine Vision 
   | 
 
The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses More...
#include <Zivid/Calibration/HandEye.h>
Public Member Functions | |
| ZIVID_CORE_EXPORT | HandEyeOutput (const Matrix4x4 &transform, const std::vector< HandEyeResidual > &residuals) | 
| Constructs a HandEyeOutput instance. More... | |
| ZIVID_CORE_EXPORT bool | valid () const | 
| Test if HandEyeOutput is valid. More... | |
| ZIVID_CORE_EXPORT | operator bool () const | 
| Test if HandEyeOutput is valid. More... | |
| ZIVID_CORE_EXPORT const Matrix4x4 & | transform () const | 
| Hand-eye transform. More... | |
| ZIVID_CORE_EXPORT const std::vector< HandEyeResidual > & | residuals () const | 
| Hand-eye calibration residuals. More... | |
| ZIVID_CORE_EXPORT std::string | toString () const | 
| Get string representation of the hand-eye calibration output More... | |
The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses
| ZIVID_CORE_EXPORT Zivid::Calibration::HandEyeOutput::HandEyeOutput | ( | const Matrix4x4 & | transform, | 
| const std::vector< HandEyeResidual > & | residuals | ||
| ) | 
Constructs a HandEyeOutput instance.
| transform | Computed hand-eye calibration transform. | 
| residuals | Per pose hand-eye residuals. | 
      
  | 
  explicit | 
Test if HandEyeOutput is valid.
| ZIVID_CORE_EXPORT const std::vector< HandEyeResidual > & Zivid::Calibration::HandEyeOutput::residuals | ( | ) | const | 
Hand-eye calibration residuals.
Feature points (for each input pose) are transformed into a common frame. A rigid transform between feature points and corresponding centroids are utilized to compute residuals for rotational and translational parts. An exception is thrown if the result is not valid.
| ZIVID_CORE_EXPORT std::string Zivid::Calibration::HandEyeOutput::toString | ( | ) | const | 
Get string representation of the hand-eye calibration output
| ZIVID_CORE_EXPORT const Matrix4x4 & Zivid::Calibration::HandEyeOutput::transform | ( | ) | const | 
Hand-eye transform.
A 4x4 matrix describing hand-eye calibration transform (either eye-in-hand or eye-to-hand). An exception is thrown if the result is not valid.
| ZIVID_CORE_EXPORT bool Zivid::Calibration::HandEyeOutput::valid | ( | ) | const | 
Test if HandEyeOutput is valid.