Zivid C++ API  1.8.1+6967bc1b-1
Defining the Future of 3D Machine Vision
Public Member Functions | List of all members
Zivid::HandEye::CalibrationOutput Class Reference

The calibration result containing the computed pose and reprojection errors for all the input poses More...

#include <Zivid/HandEye/Calibrate.h>

Public Member Functions

ZIVID_API_EXPORT CalibrationOutput (const Matrix4d &handEyeTransform, const std::vector< CalibrationResidual > &perPoseCalibrationResiduals)
 Constructs a CalibrationOutput instance. More...
 
ZIVID_API_EXPORT bool valid () const
 Test if CalibrationOutput is valid. More...
 
ZIVID_API_EXPORT operator bool () const
 Test if CalibrationOutput is valid. More...
 
const ZIVID_API_EXPORT Matrix4dhandEyeTransform () const
 Hand-eye transform. More...
 
const ZIVID_API_EXPORT std::vector< CalibrationResidual > & perPoseCalibrationResiduals () const
 Calibration residuals. More...
 
ZIVID_API_EXPORT std::string toString () const
 Get string representation of the calibration output More...
 

Detailed Description

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

Constructor & Destructor Documentation

◆ CalibrationOutput()

ZIVID_API_EXPORT Zivid::HandEye::CalibrationOutput::CalibrationOutput ( const Matrix4d handEyeTransform,
const std::vector< CalibrationResidual > &  perPoseCalibrationResiduals 
)

Constructs a CalibrationOutput instance.

Parameters
handEyeTransformComputed hand-eye calibration transform.
perPoseCalibrationResidualsPer pose calibration residuals.

Member Function Documentation

◆ handEyeTransform()

const ZIVID_API_EXPORT Matrix4d& Zivid::HandEye::CalibrationOutput::handEyeTransform ( ) 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.

◆ operator bool()

ZIVID_API_EXPORT Zivid::HandEye::CalibrationOutput::operator bool ( ) const
explicit

Test if CalibrationOutput is valid.

Returns
True if CalibrationOutput is valid.

◆ perPoseCalibrationResiduals()

const ZIVID_API_EXPORT std::vector<CalibrationResidual>& Zivid::HandEye::CalibrationOutput::perPoseCalibrationResiduals ( ) const

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 calibration residuals.

◆ toString()

ZIVID_API_EXPORT std::string Zivid::HandEye::CalibrationOutput::toString ( ) const

Get string representation of the calibration output

Returns
Calibration output as string

◆ valid()

ZIVID_API_EXPORT bool Zivid::HandEye::CalibrationOutput::valid ( ) const

Test if CalibrationOutput is valid.

Returns
True if CalibrationOutput is valid.

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