机械臂手眼标定-使用AUBO机械臂自动标定

  • Post author:
  • Post category:其他




机械臂手眼标定-使用AUBO机械臂自动标定

你好,我是小智,通过上两节的我们已经知道怎么使用已经获取的坐标数据进行计算手眼位姿,以及怎么获取标记物在相机中的位姿了,这一节我们来讲一下怎么使用AUBO的机械臂获取机械臂的位姿,以及如果使用我们的标定程序进行自动化的标定。

开源地址

github:

https://github.com/aiotrobot/handeye-calib


gitee:

https://gitee.com/ohhuo/handeye-calib

:root { --mermaid-font-family: "trebuchet ms", verdana, arial;}

机械臂位姿

手眼标定程序

相机中标定板位姿

末端与相机位姿关系

本教程一共包含五个部分:

如果上述程序使用过程中遇到问题,可以参考:

如果你对手眼标定原理感兴趣,可以参考以下文章:



介绍

  • 使用AUBO机械臂标定需要来自两个话题的信息,一个是机械臂的姿态话题,一个是相机中标定板的位姿话题



安装编译

git clone https://gitee.com/ohhuo/handeye-calib.git
cd handeye-calib
catkin_make or catkin build

安装所需文件

​ 1.安装aubo python sdk

cd src/aubo_comuniate/lib/libpy3auboi5-v1.2.3.x64
./install.sh

​ 2.安装python3 rospkg

pip3 install rospkg



配置aubo机械臂ip地址信息

cd src/aubo_comuniate/launch/

修改aubo_comuniate.launch的aubo_host为aubo机械臂所在的IP地址:

<launch>
    <arg  name="aubo_host"   default="10.55.130.223" />
    <node pkg="aubo_comuniate"  name="aubo_comuniate"  type="aubo_comuniate_py_3.py" output="screen" >
         <param name="aubo_host" value="$(arg aubo_host)" />
    </node>
</launch>



运行aubo通信节点

source devel/setup.bash
roslaunch aubo_comuniate aubo_comuniate.launch



运行标定板识别程序

请参考

手眼标定-Aruco使用与相机标定

(使用ArUco获取标志物姿,请根据相机选择标定程序)

source devel/setup.bash
roslaunch handeye-calib aruco_start_usb_cam.launch



配置标定所需话题信息

主要配置参数有

aubo_pose_topic



camera_pose_topic

。分别代表aubo机械臂的通信话题和相机中标记物的位姿话题。

通过这两个话题我们就可以拿到机械臂和标志物在相机中的位姿信息.

cd src/handeye-calib/launch
修改 aubo_hand_on_eye_calib.launch
<launch>
    <!-- The arm tool Pose Topic,Use ros geometry_msgs::Pose-->
    <arg   name="aubo_pose_topic"   default="/aubo_pose" />

    <!-- The arm marker in camera Pose Topic,Use ros geometry_msgs::Pose-->
    <arg   name="camera_pose_topic"   default="/aruco_single/pose" />

    <!-- <arg   name="camera_pose_topic"   default="/ar_pose_estimate/marker_to_camera" /> -->
    <node pkg="handeye-calib" type="aubo_hand_on_eye_calib.py" name="aubo_hand_on_eye_calib" output="screen" >
         <param name="aubo_pose_topic" value="$(arg aubo_pose_topic)" />
         <param name="camera_pose_topic" value="$(arg camera_pose_topic)" />
    </node>

</launch>



运行标定程序

 source devel/setup.bash
 roslaunch handeye-calib aubo_hand_on_eye_calib.launch



开始标定

程序运行是会对话题数据进行检测,先检测是否收到机械臂数据,如果没有会一直等待。

当检测到已经接收到数据之后,就会出现,命令提示。

命令定义如下:

r  rocord    记录一组手眼数据(当记录的数据大于程序计算所需的数据量之后会进行自动计算)
c  calculate 计算当前数据
s  save      保存数据
p  print     打印当前数据到屏幕上(格式为 type,x,y,z,rx,ry,rz 角度制)
q  quit      退出标定程序
[INFO] [1612856654.307437]: Get topic from param server: aubo_pose_topic:/aubo_pose camera_pose_topic:/aruco_single/pose
[INFO] [1612856655.311045]: Waiting aubo pose topic data ...
[INFO] [1612856656.313039]: Waiting aubo pose topic data ...
[INFO] [1612856657.314364]: Waiting aubo pose topic data ...
input:  r     record,c    calculate,s     save,q    quit:

拖拽机械臂或者用视校器移动机械臂,但要保证相机事业中依然可以看到标定板。

输入

r

记录一组手眼数据。



生成参数

完成标定之后输入

s

即可进行保存,将保存标定结果数据和计算所使用的数据。



标定结果误差分析

观察数据计算结果的标准差大小。

每次计算之后,程序都会输出不同算法下标定结果点的平均数、方差、标准差三项数值。

由于标定过程中标定板是没有发生移动的,所以我们通过机械臂的末端位置、标定结果(手眼矩阵)、标记物在相机中的位姿即可计算出标定板在机器人基坐标系下的位姿,如果标定结果准确该位姿应该是没有变化的。

可以比较最终数据的波动情况来判定标定结果的好坏。

比如:

标定板在机械臂基坐标系的位置1:

Tsai-Lenz               x            y             z            rx            ry           rz     distance
-----------  ------------  -----------  ------------  ------------  ------------  -----------  -----------
point0       -0.45432      0.0488783     0.000316595   0.0420852    -0.0245641    1.52064      0.456941
point1       -0.457722     0.054523      0.0121959    -0.0266793     0.0050922    1.53391      0.461119
point2       -0.457198     0.0535639     0.00246136    0.0252805    -0.0329136    1.51927      0.460331
point3       -0.453302     0.0618366     0.00165179    0.0405718    -0.0472311    1.53318      0.457503
point4       -0.455802     0.0589413     0.000377679   0.0222521    -0.0360589    1.51963      0.459598
point5       -0.455392     0.0615103     0.00584822    0.0365886    -0.033448     1.50684      0.459565
point6       -0.451144     0.0571198     0.00498852    0.0618337    -0.0170326    1.52463      0.454773
point7       -0.452829     0.0588266    -0.000827528   0.0324858    -0.0292652    1.52268      0.456635
point8       -0.454238     0.063634      0.00488078    0.0411648    -0.0373725    1.51611      0.458699
point9       -0.453579     0.0631788     0.00390939    0.0339742    -0.0645821    1.53168      0.457974
point10      -0.454952     0.066057     -0.00144969    0.0399135     0.0029201    1.5053       0.459725
point11      -0.459518     0.0553877    -0.00209946    0.0450864    -0.0147387    1.50702      0.462848
point12      -0.454928     0.0590754    -0.0045181     0.0297534    -0.0296122    1.52043      0.45877
point13      -0.455234     0.0527075    -0.00389213    0.0358822    -0.0260668    1.51244      0.458292
mean         -0.455011     0.0582314     0.0017031     0.0328709    -0.027491     1.51955      0.45877
var           4.21677e-06  2.16484e-05   1.84365e-05   0.000357231   0.000305579  8.29112e-05  3.79771e-06
std           0.00205348   0.00465279    0.00429378    0.0189005     0.0174808    0.00910556   0.00194877

标定板在机械臂基坐标系的位置2:

Tsai-Lenz              x            y            z           rx            ry           rz     distance
-----------  -----------  -----------  -----------  -----------  ------------  -----------  -----------
point0       -0.428394    0.052448     0.0353171    0.0259549    -0.0541487    1.57929      0.433035
point1       -0.427841    0.0448442    0.0345359    0.0454481    -0.0371304    1.55639      0.431569
point2       -0.424889    0.0486165    0.0278942    0.0455775    -0.0438353    1.57073      0.42857
point3       -0.421985    0.0485442    0.0311218    0.0138094    -0.0307286    1.55606      0.425906
point4       -0.428353    0.0454091    0.0326252    0.039192     -0.0492181    1.59177      0.431987
point5       -0.432111    0.0458869    0.0359774    0.04632      -0.0383476    1.55942      0.436028
mean         -0.427262    0.0476248    0.0329119    0.0360503    -0.0422348    1.56894      0.431183
var           9.9672e-06  6.79218e-06  7.71397e-06  0.000148499   6.11379e-05  0.000174299  1.03945e-05
std           0.00315709  0.00260618   0.0027774    0.012186      0.00781908   0.0132022    0.00322405

我们可以观察两次标定结果的距离的标准差,第一次的标准差小于的第二次的标准差,这表示第一次的标定结果好于第二次。

标准差越小,数据越聚集。

如果有不明白和有错误的地方可以留言~



作者介绍:


我是小智,机器人领域资深玩家,现深圳某独脚兽机器人算法工程师一枚


初中学习编程,高中开始学习机器人,大学期间打机器人相关比赛实现月入2W+(比赛奖金)


目前在输出机器人学习指南、论文注解、工作经验,欢迎大家关注小智,一起交流技术,学习机器人


在这里插入图片描述



版权声明:本文为qq_27865227原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。