![]() |
Zivid C++ API
1.8.1+6967bc1b-1
Defining the Future of 3D Machine Vision
|
Classes | |
class | CalibrationInput |
Binds together a robot pose and the detection result acquired from the pose More... | |
class | CalibrationOutput |
The calibration result containing the computed pose and reprojection errors for all the input poses More... | |
class | CalibrationResidual |
Binds together rotational and translational residual errors wrt. calibration transform More... | |
class | DetectionResult |
A result returned by the detectFeaturePoints(...) call More... | |
class | Pose |
Describes a robot pose More... | |
Functions | |
ZIVID_API_EXPORT std::ostream & | operator<< (std::ostream &stream, const CalibrationResidual &calibrationResidual) |
Serialize the value to a stream More... | |
ZIVID_API_EXPORT std::ostream & | operator<< (std::ostream &stream, const CalibrationInput &calibrationInput) |
Serialize the value to a stream More... | |
ZIVID_API_EXPORT std::ostream & | operator<< (std::ostream &stream, const CalibrationOutput &calibrationOutput) |
Serialize the value to a stream More... | |
ZIVID_API_EXPORT CalibrationOutput | calibrateEyeInHand (const std::vector< CalibrationInput > &input) |
Performs eye-in-hand calibration. More... | |
ZIVID_API_EXPORT CalibrationOutput | calibrateEyeToHand (const std::vector< CalibrationInput > &input) |
Performs eye-to-hand calibration. More... | |
ZIVID_API_EXPORT DetectionResult | detectFeaturePoints (const PointCloud &cloud) |
Detects feature points from a calibration object in a point cloud. More... | |
ZIVID_API_EXPORT std::ostream & | operator<< (std::ostream &stream, const DetectionResult &result) |
Serialize the value to a stream More... | |
ZIVID_API_EXPORT std::ostream & | operator<< (std::ostream &stream, const Pose &pose) |
Serialize the value to a stream More... | |
ZIVID_API_EXPORT CalibrationOutput Zivid::HandEye::calibrateEyeInHand | ( | const std::vector< CalibrationInput > & | input | ) |
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.
input | Vector of CalibrationInput instances. |
ZIVID_API_EXPORT CalibrationOutput Zivid::HandEye::calibrateEyeToHand | ( | const std::vector< CalibrationInput > & | input | ) |
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.
input | Vector of CalibrationInput instances. |
ZIVID_API_EXPORT DetectionResult Zivid::HandEye::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.
cloud | Point cloud from a frame containing an image of a calibration object |
ZIVID_API_EXPORT std::ostream& Zivid::HandEye::operator<< | ( | std::ostream & | stream, |
const CalibrationInput & | calibrationInput | ||
) |
Serialize the value to a stream
ZIVID_API_EXPORT std::ostream& Zivid::HandEye::operator<< | ( | std::ostream & | stream, |
const CalibrationOutput & | calibrationOutput | ||
) |
Serialize the value to a stream
ZIVID_API_EXPORT std::ostream& Zivid::HandEye::operator<< | ( | std::ostream & | stream, |
const CalibrationResidual & | calibrationResidual | ||
) |
Serialize the value to a stream
ZIVID_API_EXPORT std::ostream& Zivid::HandEye::operator<< | ( | std::ostream & | stream, |
const DetectionResult & | result | ||
) |
Serialize the value to a stream
ZIVID_API_EXPORT std::ostream& Zivid::HandEye::operator<< | ( | std::ostream & | stream, |
const Pose & | pose | ||
) |
Serialize the value to a stream