![]()  | 
  
    Zivid C++ API 2.12.0+6afd4961-1
    
   | 
 
#include "Zivid/Calibration/Detector.h"#include "Zivid/Calibration/Pose.h"#include "Zivid/Detail/CoreExport.h"#include <Zivid/Matrix.h>#include <vector>Go to the source code of this file.
Classes | |
| class | Zivid::Calibration::HandEyeInput | 
| Binds together a robot pose and the detection result acquired from the pose.  More... | |
| class | Zivid::Calibration::HandEyeResidual | 
| Representaton of the estimated errors of a calibrated hand-eye transform.  More... | |
| class | Zivid::Calibration::HandEyeOutput | 
| The hand-eye calibration result containing the computed pose and reprojection errors for all the input poses.  More... | |
Namespaces | |
| namespace | Zivid | 
| The main Zivid namespace. All Zivid code is found here.  | |
| namespace | Zivid::Calibration | 
Functions | |
| ZIVID_CORE_EXPORT std::ostream & | Zivid::Calibration::operator<< (std::ostream &stream, const HandEyeInput &handEyeInput) | 
| Serialize the value to a stream.   | |
| ZIVID_CORE_EXPORT std::ostream & | Zivid::Calibration::operator<< (std::ostream &stream, const HandEyeResidual &residual) | 
| Serialize the value to a stream.   | |
| ZIVID_CORE_EXPORT std::ostream & | Zivid::Calibration::operator<< (std::ostream &stream, const HandEyeOutput &handEyeOutput) | 
| Serialize the value to a stream.   | |
| ZIVID_CORE_EXPORT HandEyeOutput | Zivid::Calibration::calibrateEyeInHand (const std::vector< HandEyeInput > &inputs) | 
| Performs eye-in-hand calibration.   | |
| ZIVID_CORE_EXPORT HandEyeOutput | Zivid::Calibration::calibrateEyeToHand (const std::vector< HandEyeInput > &inputs) | 
| Performs eye-to-hand calibration.   | |