Cautions And Recommendations
Common mistakes
Image quality
Ensure the calibration object is well exposed and in focus in all images.
Keep the object within the depth of field:
Use higher \(f\)-number (smaller aperture).
Compensate with longer exposure times.
Use the same aperture setting for all images to avoid fluctuations caused by varying aperture sizes.
Capture calibration object from diverse views by exciting all six degrees of freedom of both the calibration object and the robot.
Zivid API
Zivid point clouds are given in millimeters (mm).
Therefore, ensure that robot input poses for Hand-Eye calibration also use mm for translation.
As a result, the Hand-Eye output translation values will be in millimeters (mm).
Detectable ArUco marker
If using a Zivid calibration board, ensure the ArUco marker is visible in all poses; otherwise, checkerboard detection will fail.
If using one or more ArUco markers as calibration object(s) not all markers need to be visible in every pose.
탐지 API는 탐지 실패 이유에 대한 정보를 제공합니다. 다음은 탐지 상태를 확인하는 방법의 예입니다.
const auto detectionResult = Zivid::Calibration::detectCalibrationBoard(frame);
if(detectionResult.valid())
{
std::cout << "Calibration board detected " << std::endl;
handEyeInput.emplace_back(robotPose, detectionResult);
currentPoseId++;
}
else
{
std::cout << "Failed to detect calibration board. " << detectionResult.statusDescription() << std::endl;
}
using (var frame = camera.Capture2D3D(settings))
{
var detectionResult = Detector.DetectCalibrationBoard(frame);
if (detectionResult.Valid())
{
Console.WriteLine("Calibration board detected");
handEyeInput.Add(new HandEyeInput(robotPose, detectionResult));
++currentPoseId;
}
else
{
Console.WriteLine("Failed to detect calibration board, ensure that the entire board is in the view of the camera");
}
}
detection_result = zivid.calibration.detect_calibration_board(frame)
if detection_result.valid():
print("Calibration board detected")
hand_eye_input.append(zivid.calibration.HandEyeInput(robot_pose, detection_result))
current_pose_id += 1
else:
print(f"Failed to detect calibration board. {detection_result.status_description()}")
Eye-to-hand
The calibration object is mounted on the robot end-effector and moves with the robot.
Mounting can be fixed directly to the flange or held by a gripper.
Exact mounting location is not critical (it is not necessary to know its pose relative to the end-effector).
Recommendations:
Ensure the calibration object does not move relative to the flange or gripper during robot motion.
Use rigid materials for brackets and calibration object (e.g., use Zivid On-Arm Mount to mount the Zivid calibration board to the robot).
Ensure smooth robot motion with controlled accelerations to avoid shaking or dislocation.
Ensure the calibration object is still during image acquisition (e.g., wait a few seconds after robot motion to allow vibrations to settle before capturing).
Eye-in-hand
The calibration object is stationary in the robot’s workspace.
The object’s exact location is not critical (it is not necessary to know its pose relative to the robot’s base).
The camera (mounted on the end-effector) must be able to see the calibration object from multiple perspectives.
Recommendations:
Ensure the calibration object is securely fixed and remains stationary during calibration (e.g., use Zivid Stationary Mount to mount the Zivid calibration board to a workbench).
Ensure the camera is securely fixed during calibration (e.g., using Zivid On-Arm Mount).
Environment conditions
Keep the camera temperature stable during calibration:
Ensure Thermal Stabilization is enabled to minimize temperature-related performance variations.
Perform a Warm-up procedure before starting.
Keep calibration conditions similar to the expected operating conditions.
Accuracy and recalibration
Picking accuracy depends on:
Camera calibration
Hand-eye calibration
Machine vision software
Robot positioning
Robots are repeatable but not inherently accurate due to the factors such as temperature, joint friction, payload, manufacturing tolerances.
Recommendations:
Perform mastering (zeroing) to teach the robot the exact zero position of each joint.
Calibrate the robot for improved pose accuracy.
Repeat hand-eye calibration if:
robot loses calibration.
camera is dismounted and remounted.
Perform regular recalibration (robot and/or hand-eye) to maintain system performance.
Choosing the correct method
Avoid methods that compute or require Camera Intrinsics during hand-eye calibration:
Zivid cameras are already calibrated with a complex proprietary model.
Zivid SDK provides approximations for OpenCV and Halcon models, but these lose accuracy (unlike the proprietary model).
Recommendations:
Use Zivid Hand-Eye Calibration, which leverages 3D point cloud data for extrinsic calculation.
Alternative methods based on CAD matching are also ok (they also calculate camera extrinsics from the point cloud); however, they may lack Zivid-specific optimizations.
Additional advantages of Zivid method is support for ArUco markers, which can be permanently installed in the robot cell (on-arm cameras) or on the robot (stationary cameras).
Detailed explanation
Some third party hand-eye calibration methods compute camera intrinsic parameters along with extrinsic parameters and the relative pose between the camera and the robot frame. We do not recommend these approaches because they treat a Zivid camera as an uncalibrated 2D camera, rather than a well-calibrated 3D camera.
각 Zivid 카메라 장치는 2D 컬러 카메라의 Intrinsic 파라미터를 결정하는 등 광범위한 캘리브레이션 프로세스를 거칩니다. 당사의 칼리브레이션은 잘 알려진 핀홀 카메라 모델보다 더 많은 Intrinsic 파라미터를 가진 복잡한 카메라 모델(예: OpenCV 카메라 모델)을 사용합니다. Zivid 카메라 모델은 고유하기에 내부 카메라의 Intrinsic 기능은 SDK에서 사용할 수 없습니다. 그러나 Zivid SDK는 카메라 모델에서 OpenCV 및 Halcon 모델의 근사치를 제공합니다(Camera Intrinsics 을 참조하십시오.). 근사치에서 정보가 손실될 수 있기 때문에 OpenCV 또는 Halcon Intrinsic 함수를 활용하는 핸드-아이 칼리브레이션 방법을 사용하는 것도 최선의 방법이 아닙니다.
Zivid 카메라는 3D 데이터를 제공하므로 포인트 클라우드에서 카메라 Extrinsics을 계산할 수 있습니다. Zivid 핸드-아이 칼리브레이션 방법은 이 이점을 활용하므로 이것이 권장되는 접근 방식이며 당사 카메라에서 가장 잘 작동하는 방법입니다. 포인트 클라우드에서 카메라 Extrinsics을 계산할 수 있는 가능성을 활용하는 Zivid가 아닌 대체 방법이 있습니다. 이러한 방법은 순전히 포인트 클라우드 데이터에 의존하며 예를 들어 CAD 일치를 기반으로 한 핸드-아이 칼리브레이션이 있습니다.
Zivid Hand-Eye Calibration을 사용하는 또 다른 이유는 ArUco 마커를 지원한다는 것입니다. ArUco 마커는 비교적 작아 로봇 셀에 영구적으로 설치할 수 있습니다. 특히 고정형 카메라(eye-to-hand)에 사용하기 편리하며, 로봇 플랜지와 그리퍼 사이에 설치할 수 있습니다. 반면, 로봇 장착형 카메라(eye-in-hand)의 경우, 마커를 로봇 작업 공간 어딘가에 영구적으로 설치할 수 있습니다.
Version History
SDK |
Changes |
|---|---|
2.15.0 |
탐지에 실패한 이유에 대한 정보가 detection API에 추가되었습니다. |