Zivid C++ API 2.14.0+e4a0c4a9-1
|
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. | |
ZIVID_CORE_EXPORT bool | valid () const |
Test if HandEyeOutput is valid. | |
ZIVID_CORE_EXPORT | operator bool () const |
Test if HandEyeOutput is valid. | |
ZIVID_CORE_EXPORT const Matrix4x4 & | transform () const |
Hand-eye transform. | |
ZIVID_CORE_EXPORT const std::vector< HandEyeResidual > & | residuals () const |
Hand-eye calibration residuals. | |
ZIVID_CORE_EXPORT std::string | toString () const |
Get string representation of the hand-eye calibration output. | |
The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses.
For eye-in-hand, the computed pose represents camera pose in robot end-effector frame.
For eye-to-hand, the computed pose represents camera pose in robot base frame.
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 (camera pose in robot end-effector frame for eye-in-hand or camera pose in robot base frame for eye-to-hand). |
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 computed 4x4 matrix describing hand-eye calibration transform (camera pose in robot end-effector frame for eye-in-hand or camera pose in robot base frame for eye-to-hand). The units of the translation part are the same as the units of the input.
eye-in-hand: camera pose in robot end-effector frame.
eye-to-hand: camera pose in robot base frame.
An exception is thrown if the result is not valid.
ZIVID_CORE_EXPORT bool Zivid::Calibration::HandEyeOutput::valid | ( | ) | const |
Test if HandEyeOutput is valid.