![]() |
Zivid C++ API 2.17.1+7516d437-1
|
Namespaces | |
| namespace | HandEyeLowDOF |
Classes | |
| 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 | MarkerDictionary |
| Holds information about fiducial markers such as ArUco or AprilTag for detection. More... | |
| class | Pose |
| Describes a rigid transform (rotation+translation), such as a robot pose. More... | |
Functions | |
| ZIVID_CORE_EXPORT CameraIntrinsics | intrinsics (const Camera &camera) |
| Intrinsic parameters of a given camera. | |
| ZIVID_CORE_EXPORT CameraIntrinsics | intrinsics (const Camera &camera, const Settings &settings) |
| Intrinsic parameters of a given camera and settings. | |
| ZIVID_CORE_EXPORT CameraIntrinsics | intrinsics (const Camera &camera, const Settings2D &settings2d) |
| Intrinsic parameters of a given camera and 2D settings. | |
| ZIVID_CORE_EXPORT CameraIntrinsics | estimateIntrinsics (const Frame &frame) |
| Estimate camera intrinsics for a given frame. | |
| ZIVID_CORE_EXPORT PixelMapping | pixelMapping (const Camera &camera, const Settings &settings) |
| Return mapping between 3D pixels and 2D pixels given camera and settings. | |
| ZIVID_CORE_EXPORT HandEyeOutput | calibrateEyeInHandLowDOF (const std::vector< HandEyeInput > &inputs, const HandEyeLowDOF::FixedPlacementOfCalibrationObjects &fixedObjects) |
| Performs eye-in-hand calibration for low degrees-of-freedom robots. | |
| ZIVID_CORE_EXPORT HandEyeOutput | calibrateEyeToHandLowDOF (const std::vector< HandEyeInput > &inputs, const HandEyeLowDOF::FixedPlacementOfCalibrationObjects &fixedObjects) |
| Performs eye-to-hand calibration for low degrees-of-freedom robots. | |
| ZIVID_CORE_EXPORT HandEyeOutput Zivid::Experimental::Calibration::calibrateEyeInHandLowDOF | ( | const std::vector< HandEyeInput > & | inputs, |
| const HandEyeLowDOF::FixedPlacementOfCalibrationObjects & | fixedObjects ) |
Performs eye-in-hand calibration for low degrees-of-freedom robots.
For robots with low degrees-of-freedom (DOF), that is, less than 6 DOF, the robot pose and capture inputs are not alone sufficient to uniquely identify the solution to the hand-eye calibration. This procedure additionally takes knowledge about the fixed placement of the calibration objects in the scene to provide a unique solution. For 6 DOF robots, consider using the calibrateEyeInHand function instead.
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. |
| fixedObjects | Specifies the fixed placement of calibration objects in the robot's base frame. |
| ZIVID_CORE_EXPORT HandEyeOutput Zivid::Experimental::Calibration::calibrateEyeToHandLowDOF | ( | const std::vector< HandEyeInput > & | inputs, |
| const HandEyeLowDOF::FixedPlacementOfCalibrationObjects & | fixedObjects ) |
Performs eye-to-hand calibration for low degrees-of-freedom robots.
For robots with low degrees-of-freedom (DOF), that is, less than 6 DOF, the robot pose and capture inputs are not alone sufficient to uniquely identify the solution to the hand-eye calibration. This procedure additionally takes knowledge about the fixed placement of the calibration objects in the scene to provide a unique solution. For 6 DOF robots, consider using the calibrateEyeToHand function instead.
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. |
| fixedObjects | Specifies the fixed placement of calibration objects in the robot's end-effector frame. |
| ZIVID_CORE_EXPORT CameraIntrinsics Zivid::Experimental::Calibration::estimateIntrinsics | ( | const Frame & | frame | ) |
Estimate camera intrinsics for a given frame.
The estimated parameters may be used to project 3D point cloud onto the corresponding 2D image. This function is for advanced use cases. Otherwise, use intrinsics(const Camera &camera) or intrinsics(const Camera &camera, const Settings &settings).
For a 2D+3D capture, the 2D color image and 3D point cloud may have different resolutions, depending on the pixel sampling and resampling settings used in the Settings and in the Settings::Color. This function returns intrinsics applicable for the 3D point cloud resolution.
| frame | Reference to frame instance. |
| ZIVID_CORE_EXPORT CameraIntrinsics Zivid::Experimental::Calibration::intrinsics | ( | const Camera & | camera | ) |
Intrinsic parameters of a given camera.
These intrinsic parameters are only appropriate for the resolution that the default 3D settings for the given camera provides. If planning to capture with settings other than the default 3D then use intrinsics(const Camera &camera, const Settings &settings) or intrinsics(const Camera &camera, const Settings2D &settings2d), or one can estimate the intrinsics from the frame after capture with estimateIntrinsics. Note! If there is a mismatch between 2D and 3D resolution then use intrinsics(const Camera &camera, const Settings2D &settings2d).
| camera | Reference to camera instance. |
| ZIVID_CORE_EXPORT CameraIntrinsics Zivid::Experimental::Calibration::intrinsics | ( | const Camera & | camera, |
| const Settings & | settings ) |
Intrinsic parameters of a given camera and settings.
These intrinsic parameters take into account the expected resolution of the point clouds captured with these settings.
Note: This function returns intrinsics for a fixed temperature and aperture value. The only part of Settings currently used by this function is Settings::Sampling::Pixel and Settings::Processing::Resampling::Mode.
For a 2D+3D capture, the 2D color image and 3D point cloud may have different resolutions, depending on the pixel sampling and resampling settings used in the Settings and in the Settings::Color. This function returns intrinsics applicable for the 3D point cloud resolution. You can use intrinsics(const Camera &camera, const Settings2D &settings2d) with Settings::Color for 2D intrinsics.
| camera | Reference to camera instance. |
| settings | Reference to settings instance. |
| ZIVID_CORE_EXPORT CameraIntrinsics Zivid::Experimental::Calibration::intrinsics | ( | const Camera & | camera, |
| const Settings2D & | settings2d ) |
Intrinsic parameters of a given camera and 2D settings.
These intrinsics will match the resolution of a 2D capture done using this camera with the provided Settings2D.
| camera | Reference to camera instance. |
| settings2d | Reference to a 2D settings instance. |
| ZIVID_CORE_EXPORT PixelMapping Zivid::Experimental::Calibration::pixelMapping | ( | const Camera & | camera, |
| const Settings & | settings ) |
Return mapping between 3D pixels and 2D pixels given camera and settings.
A Settings object contains specifications for capturing a 3D point cloud and (optionally) a 2D image. In the cases where the 2D image is of higher resolution than the 3D point cloud, it can be useful to know how the index/coordinate of a given 3D pixel maps to index/coordinate in the 2D image. This function provides that information via a PixelMapping object. For a given 3D index (row3d, col3d), the corresponding 2D index is:
Note that the offsets may be non-integers. This implies that there is no exact match between the 3D pixel coordinates and the 2D pixel coordinates. Rounding off the result will give the closest matching index in the 2D image.
In cases where the given Settings object specifies that 2D capture is disabled, this function returns the mapping from the point cloud to a hypothetical full-resolution 2D image. In cases where the given Settings object specifies a 2D image of lower resolution than the 3D point cloud, this function will throw an exception.
| camera | Reference to camera instance. |
| settings | Reference to settings instance. |