Zivid C++ API  2.4.2+1a2e8cfb-1
Defining the Future of 3D Machine Vision
Public Member Functions | List of all members
Zivid::Calibration::HandEyeOutput Class Reference

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 Matrix4x4transform () 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...
 

Detailed Description

The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses

Constructor & Destructor Documentation

◆ HandEyeOutput()

ZIVID_CORE_EXPORT Zivid::Calibration::HandEyeOutput::HandEyeOutput ( const Matrix4x4 transform,
const std::vector< HandEyeResidual > &  residuals 
)

Constructs a HandEyeOutput instance.

Parameters
transformComputed hand-eye calibration transform.
residualsPer pose hand-eye residuals.

Member Function Documentation

◆ operator bool()

ZIVID_CORE_EXPORT Zivid::Calibration::HandEyeOutput::operator bool ( ) const
explicit

Test if HandEyeOutput is valid.

Returns
True if HandEyeOutput is valid.

◆ residuals()

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.

Returns
Vector of hand-eye calibration residuals.

◆ toString()

ZIVID_CORE_EXPORT std::string Zivid::Calibration::HandEyeOutput::toString ( ) const

Get string representation of the hand-eye calibration output

Returns
Calibration output as string

◆ transform()

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.

Returns
Pose instance.

◆ valid()

ZIVID_CORE_EXPORT bool Zivid::Calibration::HandEyeOutput::valid ( ) const

Test if HandEyeOutput is valid.

Returns
True if HandEyeOutput is valid.

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