Zivid C++ API 2.14.0+e4a0c4a9-1
|
Classes | |
class | DetectionResult |
A result returned by the detectCalibrationBoard(...) call. More... | |
class | DetectionResultFiducialMarkers |
Stores the result returned by a detectMarkers(const Frame &frame, const std::vector<int> &markerIds, const MarkerDictionary &markerDictionary) 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 |
Representation of the estimated errors of a calibrated hand-eye transform. More... | |
class | MarkerDictionary |
Holds information about fiducial markers such as ArUco or AprilTag for detection. More... | |
class | MarkerShape |
Holds physical (3D) and image (2D) properties of a detected fiducial marker. 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. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const DetectionResultFiducialMarkers &result) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT DetectionResult | detectCalibrationBoard (Zivid::Camera &camera) |
Detects feature points from a calibration board using the given camera. | |
ZIVID_CORE_EXPORT DetectionResult | detectCalibrationBoard (const Frame &frame) |
Detects feature points from a calibration board in a frame. | |
ZIVID_CORE_EXPORT DetectionResultFiducialMarkers | detectMarkers (const Frame &frame, const std::vector< int > &allowedMarkerIds, const MarkerDictionary &markerDictionary) |
Detects fiducial markers such as ArUco markers in a frame. | |
ZIVID_CORE_EXPORT Frame | captureCalibrationBoard (Zivid::Camera &camera) |
Capture calibration board with the given camera. | |
ZIVID_CORE_EXPORT DetectionResult | detectFeaturePoints (const PointCloud &cloud) |
Detects feature points from a calibration board in a point cloud. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const HandEyeInput &handEyeInput) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const HandEyeResidual &residual) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const HandEyeOutput &handEyeOutput) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT HandEyeOutput | calibrateEyeInHand (const std::vector< HandEyeInput > &inputs) |
Performs eye-in-hand calibration. | |
ZIVID_CORE_EXPORT HandEyeOutput | calibrateEyeToHand (const std::vector< HandEyeInput > &inputs) |
Performs eye-to-hand calibration. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &os, const MarkerDictionary &dictionary) |
Serialize the dictionary to a stream. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const MarkerShape &shape) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const MultiCameraResidual &residual) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const MultiCameraOutput &multiCameraOutput) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT MultiCameraOutput | calibrateMultiCamera (const std::vector< DetectionResult > &detectionResults) |
Performs multi-camera calibration. | |
ZIVID_CORE_EXPORT std::ostream & | operator<< (std::ostream &stream, const Pose &pose) |
Serialize the value to a stream. | |
ZIVID_CORE_EXPORT HandEyeOutput Zivid::Calibration::calibrateEyeInHand | ( | const std::vector< HandEyeInput > & | inputs | ) |
Performs eye-in-hand calibration.
The procedure requires all robot poses to be different. At least 2 poses are required when using a calibration board, or 6 poses when using fiducial markers. For fiducial markers, each marker must be detected across 2 poses at minimum. An exception will be thrown if the preceding requirements are not fulfilled.
Note: the units of the input robot poses must be consistent with the units of the point clouds used to create the detection results. Zivid point clouds are, by default, in millimeters.
inputs | Vector of HandEyeInput instances. |
ZIVID_CORE_EXPORT HandEyeOutput Zivid::Calibration::calibrateEyeToHand | ( | const std::vector< HandEyeInput > & | inputs | ) |
Performs eye-to-hand calibration.
The procedure requires all robot poses to be different. At least 2 poses are required when using a calibration board, or 6 poses when using fiducial markers. For fiducial markers, each marker must be detected across 2 poses at minimum. An exception will be thrown if the preceding requirements are not fulfilled.
Note: the units of the input robot poses must be consistent with the units of the point clouds used to create the detection results. Zivid point clouds are, by default, in millimeters.
inputs | Vector of HandEyeInput instances. |
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 frame into Zivid::Calibration::detectCalibrationBoard(const Zivid::Frame &frame). 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.
detectionResults | Vector of DetectionResult instances. |
ZIVID_CORE_EXPORT Frame Zivid::Calibration::captureCalibrationBoard | ( | Zivid::Camera & | camera | ) |
Capture calibration board with the given camera.
The functionality is to be exclusively used in combination with Zivid verified calibration boards. For further information please visit Zivid help page.
This function will perform a relatively slow but high-quality point cloud capture with the given camera. This function is necessary for applications that require very high-accuracy captures, such as in-field verification/correction.
The Frame that is returned from this function may be used as input to Zivid::Calibration::detectCalibrationBoard(const Zivid::Frame &frame). You may also use Zivid::Calibration::detectCalibrationBoard(Zivid::Camera &camera) directly, which will invoke this function under the hood and yield a DetectionResult.
ZIVID_CORE_EXPORT DetectionResult Zivid::Calibration::detectCalibrationBoard | ( | const Frame & | frame | ) |
Detects feature points from a calibration board in a frame.
The functionality is to be exclusively used in combination with Zivid verified calibration boards. For further information please visit Zivid help page.
frame | A frame containing an image of a calibration board |
ZIVID_CORE_EXPORT DetectionResult Zivid::Calibration::detectCalibrationBoard | ( | Zivid::Camera & | camera | ) |
Detects feature points from a calibration board using the given camera.
The functionality is to be exclusively used in combination with Zivid verified calibration boards. For further information please visit Zivid help page.
This function will perform a relatively slow but high-quality point cloud capture with the given camera. This function is necessary for applications that require very high-accuracy DetectionResult, such as in-field verification/correction.
camera | Camera to be used to capture the calibration board |
ZIVID_CORE_EXPORT DetectionResult Zivid::Calibration::detectFeaturePoints | ( | const PointCloud & | cloud | ) |
Detects feature points from a calibration board in a point cloud.
The functionality is to be exclusively used in combination with Zivid verified calibration boards. For further information please visit Zivid help page.
This method is deprecated as of SDK 2.9. Instead you should use Zivid::Calibration::detectCalibrationBoard(const Zivid::Frame &frame) or Zivid::Calibration::detectCalibrationBoard(Zivid::Camera &camera).
cloud | Point cloud from a frame containing an image of a calibration board |
ZIVID_CORE_EXPORT DetectionResultFiducialMarkers Zivid::Calibration::detectMarkers | ( | const Frame & | frame, |
const std::vector< int > & | allowedMarkerIds, | ||
const MarkerDictionary & | markerDictionary ) |
Detects fiducial markers such as ArUco markers in a frame.
Only markers with integer IDs are supported. For further information on fiducial markers see this wikipedia page. For more information on ArUco markers specifically, refer to the OpenCV documentation. The Frame need not contain all markers listed in allowedMarkerIds for a successful detection.
frame | A frame containing an image of one or several fiducial markers |
allowedMarkerIds | A list of the IDs of markers to be detected |
markerDictionary | The marker dictionary that describes the appearance of each marker |
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | os, |
const MarkerDictionary & | dictionary ) |
Serialize the dictionary to a stream.
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | stream, |
const DetectionResult & | result ) |
Serialize the value to a stream.
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | stream, |
const DetectionResultFiducialMarkers & | result ) |
Serialize the value to a stream.
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 HandEyeOutput & | handEyeOutput ) |
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 MarkerShape & | shape ) |
Serialize the value to a stream.
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | stream, |
const MultiCameraOutput & | multiCameraOutput ) |
Serialize the value to a stream.
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | stream, |
const MultiCameraResidual & | residual ) |
Serialize the value to a stream.
ZIVID_CORE_EXPORT std::ostream & Zivid::Calibration::operator<< | ( | std::ostream & | stream, |
const Pose & | pose ) |
Serialize the value to a stream.