Zivid C++ API 2.13.1+18e79e79-1
Zivid::Calibration::HandEyeInput Class Reference

Binds together a robot pose and the detection result acquired from the pose. More...

#include <Zivid/Calibration/HandEye.h>

Public Member Functions

ZIVID_CORE_EXPORT HandEyeInput (const Pose &robotPose, const DetectionResult &detectionResult)
 Constructs a HandEyeInput instance from a calibration board detection result.
 
ZIVID_CORE_EXPORT HandEyeInput (const Pose &robotPose, const DetectionResultFiducialMarkers &detectionResult)
 Constructs a HandEyeInput instance from a fiducial marker detection result.
 
ZIVID_CORE_EXPORT const PoserobotPose () const
 Robot pose for the detected object(s).
 
ZIVID_CORE_EXPORT const DetectionResultdetectionResult () const
 Feature detection result.
 
ZIVID_CORE_EXPORT std::string toString () const
 Get string representation of the hand-eye calibration input.
 

Detailed Description

Binds together a robot pose and the detection result acquired from the pose.

Constructor & Destructor Documentation

◆ HandEyeInput() [1/2]

ZIVID_CORE_EXPORT Zivid::Calibration::HandEyeInput::HandEyeInput ( const Pose & robotPose,
const DetectionResult & detectionResult )

Constructs a HandEyeInput instance from a calibration board detection result.

Parameters
robotPoseRobot pose for detected feature points.
detectionResultCalibration board detection result.

◆ HandEyeInput() [2/2]

ZIVID_CORE_EXPORT Zivid::Calibration::HandEyeInput::HandEyeInput ( const Pose & robotPose,
const DetectionResultFiducialMarkers & detectionResult )

Constructs a HandEyeInput instance from a fiducial marker detection result.

Parameters
robotPoseRobot pose for the detected markers.
detectionResultFiducial marker detection result.

Member Function Documentation

◆ detectionResult()

ZIVID_CORE_EXPORT const DetectionResult & Zivid::Calibration::HandEyeInput::detectionResult ( ) const

Feature detection result.

Only use this function if the HandEyeInput was created from a DetectionResult object. Throws an exception otherwise.

Returns
Detection result.

◆ robotPose()

ZIVID_CORE_EXPORT const Pose & Zivid::Calibration::HandEyeInput::robotPose ( ) const

Robot pose for the detected object(s).

Returns
Robot pose.

◆ toString()

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

Get string representation of the hand-eye calibration input.

Returns
Hand-eye calibration input as string.

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