任意机械臂 + RobotDK + Python:通过触碰测试验证手眼标定的结果
备注
本教程仅在UR5e和Yaskawa H10上进行了测试,并且仅适用于RoboDK支持的机器人。
介绍
有时很难衡量手眼标定的准确性。因此,我们创建了一个触碰测试可以让用户轻松地验证其准确性。在这个测试中,我们使用 RoboDK 来移动机器人。此示例适用于两种手眼标定类型的结果,即眼在手上(Eye-in-Hand)和眼在手外(Eye-to-Hand)。触碰测试的过程包括将 Zivid 标定对象 放置在相机的 FOV 中,捕获它,并控制机器人在特定点触碰它。完成触碰后,您可以移动 Zivid 标定对象并指示机器人再次触碰它。您可以根据需要多次重复此过程。唯一的两个限制是机器人的工作范围和相机的 FOV 。
在下图中,您可以看到触碰测试的预期结果。
备注
触碰的准确性取决于机器人标定误差、手眼标定误差、TCP 标定误差和标定物体位姿的估计误差。
要求
已安装 Zivid software ,如果在Linux 上运行,则包括Zivid Tools。
已安装 Zivid-Python 。
已安装 RoboDK software 。
在 Robodk robot library 中有一台数字孪生的机器人。
一个 .yaml 文件,包含了手眼标定产生的手眼变换矩阵。
包含定义了尖头手眼验证工具(Pointed Hand-Eye Verification Tool)的变换矩阵的.yaml文件。
尖头手眼验证工具(Pointed Hand-Eye Verification Tool)
本教程使用了一个尖头手眼验证工具作为触碰工具。该工具适用于UR5e(ISO 9409-1-50-4-M6) 和Yaskawa HC10 (ISO 9409-1-63-4-M6) 。
pointed-hand-eye-verification-tool.STL
- STL格式的CAD模型,可用于3D打印。pointed-hand-eye-verification-tool.STEP
- STEP格式的CAD模型,可以加载到RoboDK中。pointed-hand-eye-verification-tool.yaml
- 用于保存转换矩阵的YAML文件,需要作为与本教程相关的代码示例的输入参数之一。
下图展示的即为尖头手眼验证工具(Pointed Hand-Eye Verification Tool)。
手臂安装
在本教程中,我们在机器人末端执行器和尖头手眼验证工具之间使用了 Zivid On-Arm Mount Extender 和 Zivid On-Arm Mount 。这些支架增加了机器人末端执行器和尖头手眼验证工具之间的距离。您可以在下图中找到为每个安装座添加的测量值。
on-arm-mounts.yaml
文件包含了安装在机器人末端执行器和尖头手眼验证工具之间的两个支架的转换矩阵。有关安装支架的更多详细信息,请查看 on-arm camera mount datasheet 和 on-arm mount extender datasheet 。
如果您已经设置了RoboDK环境并且已连接到您的机器人,则可以跳转到 为触碰测试创建捕获位姿 的步骤
设置RoboDK环境
RoboDK .rdk 文件存储了有关机器人、目标位姿和环境的信息。执行触碰测试所需的 .rdk 文件中的组件包括:
机器人模型文件(.robot)
一个目标位姿(在本教程演示的示例中,它被命名为”touch_test_pose”)
机器人环境的虚拟模型(可选)
所用相机的 CAD 模型,例如 Zivid 2 CAD file (可选)
尖头手眼验证工具的CAD模型(可选)
将机器人添加到RoboDK环境
首先打开RoboDK程序并添加将要使用的机器人。添加机器人需要在GUI中从 File -> Open online library 打开库。通过该界面找到与您的模型匹配的机器人,将鼠标悬停在其上并选择 Open 。如果机器人没有出现在工作站中,请选择 Download 并将其拖放到.rdk环境中。 Select a robot RoboDK tutorial 中也对此进行了描述。
通过RoboDK连接到机器人
警告
根据所用机器人的品牌,可能需要驱动程序设置才能连接到 RoboDK。有关此设置的帮助,请查看 RoboDK 文档中的机器人提示部分。例如,这是针对 ABB robots 的建议。
在运行Touch Test脚本之前,首先需要使用RoboDK的接口连接到机器人。在RoboDK GUI中导航到 Connect -> Connect Robot 。这将打开一个侧面板,您可以在其中输入机器人IP和端口号。
备注
大多数机器人的控制器或平板电脑控制器上都有远程模式。请确保您的机器人处于远程模式以便能够建立连接。
要连接到机器人,您必须知道它的IP地址,它应该可以在机器人控制面板中找到/列出。按照 connecting to the robot for RoboDK 中的步骤操作。另一个需要验证的连接是端口号。除非之前进行了更改,否则驱动程序附带的默认编号应该可以使用。
请点击 Connect ,如果 Connection status 框为绿色,则可以使用RoboDK界面控制机器人了。如果它是红色的,请确保您拥有正确的端口号和IP地址。如果它仍然是红色的,请查看本教程末尾的RoboDK故障排除章节。
为触碰测试创建捕获位姿
了解 how to create a target in RoboDK 来保存触碰测试的捕获位姿。
可以通过两种方式使用RoboDK创建位姿:
使用示教器将机器人物理移动到所需的位姿,然后通过RoboDK连接并记录这些位姿
通过RoboDK远程移动机器人来创建和保存这些位姿
小技巧
如果您通过RoboDK移动机器人,但是机器人的移动速度太快或太慢,请查看链接 set the robot speed in RoboDK 进行调整。设置好速度后,记得右键单击您创建的程序并标记 Run on the robot ,然后再次右键单击并选择 Run。
在创建Touch Test Capture Pose之前,您必须考虑计划放置 Zivid 标定对象 的位置。如果是Eye-in-Hand,请确保它位于相机的 FOV 中。如果是Eye-to-Hand,请确保机器人不会在拍照时挡住Zivid标定对象。触碰测试只需要一个位姿。您可以从下图中看到RoboDK中的显示画面。
运行触碰测试
在运行脚本之前,需要打开.rdk文件并连接到机器人。 The script can be found in the Zivid Python Samples ;它使用了如下所示的命令行参数。
type_group.add_argument("--eih", "--eye-in-hand", action="store_true", help="eye-in-hand configuration")
type_group.add_argument("--eth", "--eye-to-hand", action="store_true", help="eye-to-hand configuration")
parser.add_argument("--ip", required=True, help="IP address of the robot controller")
parser.add_argument(
"--target-keyword",
required=True,
help="RoboDK target name representing a robot pose at which the calibration object is in the field of view of the camera",
)
parser.add_argument(
"--tool-yaml",
required=True,
help="Path to YAML file that represents the Pointed Hand-Eye Verification Tool transformation matrix",
)
parser.add_argument(
"--mounts-yaml",
required=False,
help="Path to YAML file that represents the on-arm mounts transformation matrix",
)
parser.add_argument(
"--hand-eye-yaml",
required=True,
help="Path to the YAML file that contains the Hand-Eye transformation matrix",
)
subparsers = parser.add_subparsers(dest="calibration_object", required=True, help="Calibration object type")
subparsers.add_parser("checkerboard", help="Verify using Zivid calibration board")
marker_parser = subparsers.add_parser("marker", help="Verify using ArUco marker")
marker_parser.add_argument(
"--dictionary",
required=True,
choices=list(zivid.calibration.MarkerDictionary.valid_values()),
help="Dictionary of the targeted ArUco marker",
)
marker_parser.add_argument(
"--id", nargs=1, required=True, type=int, help="ID of ArUco marker to be used for verification"
)
该脚本按以下步骤运行:
机器人移动到之前定义的捕获位姿。
要求用户将 Zivid 标定物体放入 FOV 并按下 Enter 。
相机将捕获 Zivid 标定对象,计算触碰点的位姿并显示给用户。
当用户按下 Enter 键时,机器人会在特定点触碰 Zivid 标定对象。
按下 Enter 键后,机器人向后拉并返回到捕获位姿。
此时,可以移动 Zivid 标定对象以在不同位置执行触碰测试。
用户需要输入”y”或者”n”来重复或中止触摸测试。
关于脚本
要使RoboDK手眼标定验证脚本能够正常运行,需要三个额外的Python文件。
robodk_tools.py , 用于配置机器人。
save_load_matrix.py ,用于在YAML文件中保存和加载矩阵。
该脚本分别运行以下步骤:
连接到机器人
首先,我们使用IP地址连接到机器人。然后我们将得到一个用于与模拟器建立链接的 rdk
对象和一个包含了各种机器人配置参数的 robot
对象。
rdk, robot = connect_to_robot(user_options.ip)
设置机器人速度和加速度
机器人配置的最后一步是定义机器人的速度和加速度。
set_robot_speed_and_acceleration(robot, speed=100, joint_speed=100, acceleration=50, joint_acceleration=50)
加载尖头手眼验证工具的转换矩阵
然后加载定义尖头手眼验证工具的转换矩阵。
print("Loading the Pointed Hand-Eye Verification Tool transformation matrix from a YAML file")
tool_base_to_tool_tip_transform = load_and_assert_affine_matrix(user_options.tool_yaml)
定义TCP转换矩阵
然后我们需要定义工具中心点 ( TCP
)。首先,程序将检查用户是否提供了包含手臂安装支架转换矩阵的.yaml文件。如果用户没有提供任何手臂安装支架转换矩阵,那么我们假设尖头手眼验证工具是直接连接到机器人的末端执行器。因此, TCP
矩阵等同于尖头手眼验证工具矩阵。
if user_options.mounts_yaml:
print("Loading the on-arm mounts transformation matrix from a YAML file")
flange_to_tool_base_transform = load_and_assert_affine_matrix(user_options.mounts_yaml)
flange_to_tcp_transform = flange_to_tool_base_transform @ tool_base_to_tool_tip_transform
else:
flange_to_tcp_transform = tool_base_to_tool_tip_transform
移动到捕获位姿
机器人移动到 capture_pose
,这是从运行此示例时打开的.rdk文件中获取的。
capture_pose = get_robot_targets(rdk, target_keyword=user_options.target_keyword)
if not capture_pose:
raise IndexError(
"The list of poses retrieved from RoboDK is empty...\nMake sure that you have created a Capture Pose and that you introduced the right keyword for it."
)
robot.MoveJ(capture_pose[0])
放置 Zivid 标定对象
下一步是确保用户已将 Zivid 标定对象放置在相机的 FOV 中。
print("\nPlace the calibration object in the FOV of the camera.")
input("Press enter to start.")
Zivid 标定对象检测和位姿估计
按下 Enter
后,将捕获 Zivid 标定对象并估计其在相机坐标系中的位姿。
frame, bgra_image = _assisted_capture(camera)
camera_to_calibration_object_transform = _estimate_calibration_object_pose(frame, user_options)
将 Zivid 标定对象位姿从相机坐标系转换到机器人基坐标系
print("Calculating the calibration object pose in robot base frame")
base_to_calibration_object_transform = _get_base_to_calibration_object_transform(
user_options,
camera_to_calibration_object_transform,
robot,
)
如需了解此转换背后的数学原理,请查看 手眼标定解决方案 。
获得触碰位姿
由于我们控制机器人移动到的触碰位姿是末端执行器(法兰)的位姿,因此我们还需要考虑 TCP
。
print("Calculating pose for robot to touch the calibration object")
touch_pose = base_to_calibration_object_transform @ np.linalg.inv(flange_to_tcp_transform)
获取接近位姿
我们将接近位姿定义为与触碰位姿在Z轴上存在一定偏移量的一个位姿,比如选择为-140mm。
print("Calculating pose for the robot to approach the calibration object")
touch_pose_offset = np.identity(4)
touch_pose_offset[2, 3] = -140
approach_pose = touch_pose @ touch_pose_offset
触碰Zivid标定对象
在接近并触碰 Zivid 标定对象之前,计算出的触碰位姿显示给用户。
然后用户可以按下 Enter
来允许机器人执行触碰。
_draw_coordinate_system(frame, camera_to_calibration_object_transform, bgra_image)
input("\nClose the window and press enter to the touch the calibration object...")
在触碰 Zivid 标定对象时,机器人首先通过关节运动方式移动到接近位姿。然后沿直线运动方式移动到触碰位姿。此时,用户可以靠近 Zivid 标定对象并目视检查所执行触碰的准确性。
print("Touching calibration object")
robot.MoveJ(Mat(approach_pose.tolist()))
robot.MoveL(Mat(touch_pose.tolist()))
远离 Zivid 校准对象
该程序需要用户按下 Enter
让机器人远离 Zivid 标定对象并返回到捕获位姿。
input("\nPress enter to pull back and return to the capture pose...")
robot.MoveL(Mat(approach_pose.tolist()))
robot.MoveJ(capture_pose[0])
再次触碰 Zivid 标定对象
此时,可以移动 Zivid 标定对象以在相机的 FOV 内的不同位置执行触碰测试。需要用户输入 “y” 或 “n” 以重复或中止触碰测试。
print("\nThe calibration object can be moved at this time.")
answer = _yes_no_prompt("Perform another touch?")
if answer == "n":
break
RoboDK疑难解答
机器人以与预期不同的配置运动
在Windows上开启防火墙的情况下进行连接
备注
此方法在 Windows 10 上进行了测试。
检查驱动阻塞
在连接到运行Windows的计算机时,请注意防火墙可能会阻止与机器人的连接。一种方法是完全禁用防火墙,但通常不建议这样做,因为它会使您的系统易于受到攻击。
另外的方法是您可以在Windows防火墙中添加新的规则,以仅允许与您使用的机器人的驱动程序和IP地址进行通信。要找到这两个属性,请通过选择 connect to robot 展开 more options 面板。在这种情况下,驱动程序是 apiur 。
打开系统上的Windows Defender 防火墙并进入 Advanced settings 。在这里您可以更改规则以允许与控制机器人所需的驱动程序进行通信。
如果机器人驱动程序上有阻塞标志,请检查入站规则。如果驱动程序被阻止,请禁用此规则,否则防火墙会阻止其通信。
禁用此规则后,请检查RoboDK软件是否可以连接到机器人。如果仍然无法连接到机器人,则需要制定一条规则,专门允许驱动程序与机器人进行通信。
创建新的入站规则
通过单击 New Rule… ,您可以创建并定义一个允许您的计算机和机器人之间进行通信的规则。
首先,您需要在第一页选择 Custom 选项,在第二页选择 All programs 选项。您可以在下面找到它。
在下一页您需要选择TCP作为协议,然后选择特定的本地端口并输入与RoboDK中匹配的端口号。
下一步是设置IP地址。在 Which remote IP address does this rule apply to? 下选择 These IP addresses 。然后点击 Add 并设置与RoboDK中匹配的IP。
点击 OK ` 和 :guilabel:`Next ,选择 Allow all connections 并在下一页选中所有复选框。
最后,请为该规则选择一个合适的名称,点击 Finish 就可以了!