 |
Zivid C++ API
1.8.1+6967bc1b-1
Defining the Future of 3D Machine Vision
|
Go to the documentation of this file.
63 class CalibrationResidual
94 class CalibrationInput
116 DetectionResult m_result;
125 class CalibrationOutput
166 std::vector<CalibrationResidual> m_perPoseCalibrationResiduals;
ZIVID_API_EXPORT std::string toString() const
Get string representation of the calibration residual
ZIVID_API_EXPORT CalibrationOutput calibrateEyeToHand(const std::vector< CalibrationInput > &input)
Performs eye-to-hand calibration.
const ZIVID_API_EXPORT std::vector< CalibrationResidual > & perPoseCalibrationResiduals() const
Calibration residuals.
ZIVID_API_EXPORT double rotation() const
Rotational residual in degrees.
const ZIVID_API_EXPORT Matrix4d & handEyeTransform() const
Hand-eye transform.
ZIVID_API_EXPORT CalibrationResidual(double rotation, double translation)
Constructs a calibration residual instance.
ZIVID_API_EXPORT double translation() const
Translational residual in millimeters.
Matrix< double, 4, 4 > Matrix4d
Matrix of size 4x4 containing doubles
Definition: Matrix.h:297
ZIVID_API_EXPORT CalibrationOutput(const Matrix4d &handEyeTransform, const std::vector< CalibrationResidual > &perPoseCalibrationResiduals)
Constructs a CalibrationOutput instance.
ZIVID_API_EXPORT CalibrationOutput calibrateEyeInHand(const std::vector< CalibrationInput > &input)
Performs eye-in-hand calibration.
The main Zivid namespace. All Zivid code is found here
Definition: Application.h:52
ZIVID_API_EXPORT bool valid() const
Test if CalibrationOutput is valid.
#define ZIVID_API_EXPORT
Definition: APIExport.h:56
ZIVID_API_EXPORT std::string toString() const
Get string representation of the calibration output
ZIVID_API_EXPORT std::ostream & operator<<(std::ostream &stream, const CalibrationResidual &calibrationResidual)
Serialize the value to a stream