Zivid C++ API 2.9.0+4dbba385-1
Defining the Future of 3D Machine Vision
Classes | Functions
Zivid::Calibration Namespace Reference

Classes

class  DetectionResult
 A result returned by the detectFeaturePoints(...) call More...
 
class  HandEyeInput
 Binds together a robot pose and the detection result acquired from the pose More...
 
class  HandEyeOutput
 The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses More...
 
class  HandEyeResidual
 Representaton of the estimated errors of a calibrated hand-eye transform More...
 
class  MultiCameraOutput
 The results from a multi-camera calibration process More...
 
class  MultiCameraResidual
 Representation of the estimated errors of a multi-camera calibration More...
 
class  Pose
 Describes a robot pose More...
 

Functions

ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const DetectionResult &result)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT DetectionResult detectFeaturePoints (const PointCloud &cloud)
 Detects feature points from a calibration object in a point cloud. More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const HandEyeInput &handEyeInput)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const HandEyeResidual &residual)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const HandEyeOutput &handEyeOutput)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT HandEyeOutput calibrateEyeInHand (const std::vector< HandEyeInput > &inputs)
 Performs eye-in-hand calibration. More...
 
ZIVID_CORE_EXPORT HandEyeOutput calibrateEyeToHand (const std::vector< HandEyeInput > &inputs)
 Performs eye-to-hand calibration. More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const MultiCameraResidual &residual)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const MultiCameraOutput &multiCameraOutput)
 Serialize the value to a stream More...
 
ZIVID_CORE_EXPORT MultiCameraOutput calibrateMultiCamera (const std::vector< DetectionResult > &detectionResults)
 Performs multi-camera calibration. More...
 
ZIVID_CORE_EXPORT std::ostream & operator<< (std::ostream &stream, const Pose &pose)
 Serialize the value to a stream More...
 

Function Documentation

◆ calibrateEyeInHand()

ZIVID_CORE_EXPORT HandEyeOutput Zivid::Calibration::calibrateEyeInHand ( const std::vector< HandEyeInput > &  inputs)

Performs eye-in-hand calibration.

The procedure requires feature point sets acquired at the minimum from two poses. All the input poses have to be different. The feature point sets cannot be empty. All the feature point sets have to have same number of feature points. An exception will be thrown if the above requirements are not fulfilled.

Parameters
inputsVector of HandEyeInput instances.
Returns
Instance of HandEyeOutput.

◆ calibrateEyeToHand()

ZIVID_CORE_EXPORT HandEyeOutput Zivid::Calibration::calibrateEyeToHand ( const std::vector< HandEyeInput > &  inputs)

Performs eye-to-hand calibration.

The procedure requires feature point sets acquired at the minimum from two poses. All the input poses have to be different. The feature point sets cannot be empty. All the feature points have to have same number of elements. An exception will be thrown if the above requirements are not fulfilled.

Parameters
inputsVector of HandEyeInput instances.
Returns
Instance of HandEyeOutput.

◆ calibrateMultiCamera()

ZIVID_CORE_EXPORT MultiCameraOutput Zivid::Calibration::calibrateMultiCamera ( const std::vector< DetectionResult > &  detectionResults)

Performs multi-camera calibration.

Multi-camera calibration is used in a multi-camera setup to find the pose of secondary cameras in the frame of a designated primary camera, e.g. to combine points clouds into a single frame of reference.

The input is generated by imaging the same checkerboard from each camera and inserting the resulting point clouds into detectFeaturePoints. Add the resulting DetectionResult objects to a vector with the first element corresponding to the primary camera.

The returned object contains a vector of transforms, which provides the pose of camera[i] in the frame of camera[0]. Apply transform[i] to the points from camera[i] to get the same points in the frame of camera[0]. The returned object also contains a vector of residuals corresponding to each transform.

Parameters
detectionResultsVector of DetectionResult instances.
Returns
A MultiCameraOutput instance.

◆ detectFeaturePoints()

ZIVID_CORE_EXPORT DetectionResult Zivid::Calibration::detectFeaturePoints ( const PointCloud cloud)

Detects feature points from a calibration object in a point cloud.

The functionality is to be exclusively used in combination with Zivid verified checkerboards. For further information please visit Zivid help page.

This method is deprecated as of SDK 2.9. Instead you should use the version of detectFeaturePoints that takes a Zivid::Frame or Zivid::Camera. See Zivid::Experimental::Calibration::detectFeaturePoints(const Zivid::Frame &frame) and Zivid::Experimental::Calibration::detectFeaturePoints(Zivid::Camera &camera).

Parameters
cloudPoint cloud from a frame containing an image of a calibration object

◆ operator<<() [1/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const DetectionResult result 
)

Serialize the value to a stream

◆ operator<<() [2/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const HandEyeInput handEyeInput 
)

Serialize the value to a stream

◆ operator<<() [3/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const HandEyeOutput handEyeOutput 
)

Serialize the value to a stream

◆ operator<<() [4/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const HandEyeResidual residual 
)

Serialize the value to a stream

◆ operator<<() [5/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const MultiCameraOutput multiCameraOutput 
)

Serialize the value to a stream

◆ operator<<() [6/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const MultiCameraResidual residual 
)

Serialize the value to a stream

◆ operator<<() [7/7]

ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< ( std::ostream &  stream,
const Pose pose 
)

Serialize the value to a stream