注意事项和建议
图像质量
保证标定对象的图像充分曝光且对焦是非常重要的。为确保标定对象处于 depth of field ,建议使用更大的
Zivid API
Zivid点云以毫米为单位。 Zivid API中手眼输出的位姿的平移部分也以mm为单位。因此,手眼标定输入的机器人位姿的平移部分也必须以mm为单位。
可检测的ArUco标记
如果标定对象是 Zivid calibration board ,请确保 ArUco 标记在所有位姿下都可见。否则,算法在尝试检测棋盘格时将失败。另一方面,当使用一个或多个 ArUco 标记作为标定对象时,并非所有标记都需要在所有位姿下都可见。
The detection API provides information about why the detection failed. The following shows an example of how to check the detection status:
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 = Zivid.NET.Calibration.Detector.CaptureCalibrationBoard(camera))
{
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
在eye-to-hand标定过程中,标定对象安装在机器人末端执行器上并随机器人移动。它可以直接固定在工具法兰上或由夹具固定。安装的确切位置并不重要,因为不必知道标定对象和末端执行器之间的相对位姿。重要的是标定对象在运动过程中不会出现相对于工具法兰或夹具的位移,它必须被良好地固定住或被夹具紧紧地抓住。建议使用由刚性材料制成的安装支架以及标定板。保证标定对象在图像采集期间保持不动是非常重要的。建议在机器人和标定对象定位完成等待几秒钟,直到整个结构从运动后的振动中稳定下来。应通过控制机器人的加速度使其平稳地运动,以避免标定对象发生晃动或错位。
Eye-in-hand
在eye-in-hand标定过程中,标定对象是固定放置在机器人工作区内的,这个固定位置需要保证安装在机器人上的相机可以从不同的视角观测到它。 标定对象的确切位置并不重要,因为不必知道其相对于机器人基座的位姿。 但是,标定对象在标定期间应牢牢固定住,不得移动。
环境条件
温度变化对性能有一些影响。因此建议确保手眼标定过程中的温度在一定程度上保持稳定。这可以通过 预热 程序实现。最好选择与实际部署类似的工作环境进行标定。如需进一步降低与温度相关的性能因素的影响,请启用 Thermal Stabilization(热稳定功能)。
选择正确的方法
一些手眼标定方法会计算相机内参以及外参和相机与机器人坐标系之间的相对位姿。我们不推荐这些方法,因为它们将Zivid相机视为未标定过的2D相机,而不是经过良好标定的3D相机。
每台Zivid相机都经过了一系列的标定过程,其中包括了2D彩色相机的内参。我们的标定使用了复杂的相机模型,其内参数量比一些众所周知的针孔相机模型(例如OpenCV相机模型)更多。由于Zivid相机模型是专有的,因此我们的内部相机内参无法通过SDK获取。但是,Zivid SDK确实从我们的相机模型中提供了OpenCV和Halcon模型的近似数据(请参阅 相机内参 )。由于一些信息在近似数据中丢失,因此使用OpenCV或Halcon格式内参的手眼标定方法也不是最佳方法。
由于Zivid相机提供了3D数据,因此可以通过点云计算相机外参。 Zivid手眼标定方法利用了这一优势,这就是为什么它是推荐的标定方法,也是最适合我们相机的方法。当然也有可替代的第三方方法,它们通过点云计算相机外参。这些方法完全依赖于点云数据,比如基于CAD匹配的手眼标定方法。
使用 Zivid 手眼标定的另一个益处是其支持 ArUco 标记,这些标记相对较小,因此可以永久安装在机器人单元中。它们对于固定安装的相机(眼在手外)特别方便,因为它们可以安装在机器人法兰和夹持器之间。另一方面,对于手臂安装的相机(眼在手上),标记可以永久安装在机器人工作空间的某个位置。
准确度和重新标定
视觉引导机器人系统的拾取精度取决于相机、手眼标定、机器视觉软件和机器人定位的综合精度。机器人通常具有很高的重复定位精度,但并不准确。温度、关节摩擦力、有效载荷和制造公差是导致机器人偏离其预编程定位的一些因素。但是,可以通过标定机器人本身来提高机器人的位姿精度,强烈建议将其用于具有影响拾取精度的多种因素的复杂系统。如果机器人失去校准,拾取精度将下降。重复标定(机器人和/或手眼)可以补偿这种恶化的性能。从固定结构或机器人上拆卸相机并将其重新安装后,也需要再次执行手眼标定。
阅读更多关于 手眼标定的残差.
Version History
SDK |
Changes |
---|---|
2.15.0 |
Information about why the detection failed added to detection API. |