![]() |
Zivid C++ API
1.8.1+6967bc1b-1
Defining the Future of 3D Machine Vision
|
Binds together rotational and translational residual errors wrt. calibration transform More...
#include <Zivid/HandEye/Calibrate.h>
Public Member Functions | |
ZIVID_API_EXPORT | CalibrationResidual (double rotation, double translation) |
Constructs a calibration residual instance. More... | |
ZIVID_API_EXPORT double | rotation () const |
Rotational residual in degrees. More... | |
ZIVID_API_EXPORT double | translation () const |
Translational residual in millimeters. More... | |
ZIVID_API_EXPORT std::string | toString () const |
Get string representation of the calibration residual More... | |
Binds together rotational and translational residual errors wrt. calibration transform
ZIVID_API_EXPORT Zivid::HandEye::CalibrationResidual::CalibrationResidual | ( | double | rotation, |
double | translation | ||
) |
Constructs a calibration residual instance.
rotation | Residual for rotation part. |
translation | Residual for translation part. |
ZIVID_API_EXPORT double Zivid::HandEye::CalibrationResidual::rotation | ( | ) | const |
Rotational residual in degrees.
ZIVID_API_EXPORT std::string Zivid::HandEye::CalibrationResidual::toString | ( | ) | const |
Get string representation of the calibration residual
ZIVID_API_EXPORT double Zivid::HandEye::CalibrationResidual::translation | ( | ) | const |
Translational residual in millimeters.