你們好,我是小智,最近折騰了一段時間的機械臂的手眼標定,相關資料挺多的,但使用起來都比較複雜,新手通常比較難搞懂。因而想作一個比較簡單易懂易用的手眼標定程序。node
項目開源地址:gitee.com/ohhuo/hande…git
本程序包目前僅針對眼在手上的標定,經過輸入兩組以上的機械臂姿態信息(x,y,z,rx,ry,rz)和裝在機械手上的相機所識別的標誌物的姿態信息,通過程序計算可輸出,機械臂末端和相機之間的座標變換矩陣。算法
基礎使用是在獲得多組機械臂位姿與機械臂末端相機位姿以後直接使用本程序進行計算機械臂末端與相機之間的位姿關係。bash
機械臂位姿能夠經過示教器或者SDK進行獲取markdown
相機中標定板位姿咱們能夠經過ArUco或者ArTookit等工具得到app
咱們使用通常讀到的(X,Y,Z,RX,RY,RZ)六個數據表示ide
git clone https://gitee.com/ohhuo/handeye-calib.git
cd handeye-calib
catkin_make or catkin build
複製代碼
<launch>
<!-- <arg name="base_handeye_data" default="The file path of handeye data." /> -->
<arg name="base_handeye_data" default="$(find handeye-calib)/config/base_hand_on_eye_test_data.csv" />
<node pkg="handeye-calib" type="base_hand_on_eye_calib.py" name="base_hand_on_eye_calib" output="screen" >
<param name="base_handeye_data" value="$(arg base_handeye_data)" />
</node>
</launch>
複製代碼
source devel/setup.bash
roslaunch handeye-calib base_hand_on_eye_calib.launch
複製代碼
程序會根據配置文件中的座標進行計算,最終輸出以下數據(單位毫米,弧度制):數據包含不一樣算法下計算結果,以及計算結果的標準差和方差等數據。工具
algoritihms x y z rx ry rz distance
------------- --------- ----------- ---------- --------- ---------- ------- ----------
Daniilidis 0.0254407 -0.00388589 0.00626286 -1.34278 -0.0699976 91.0318 0.0264868
Horaud 0.035229 -0.0151477 0.0185151 1.65751 0.943546 89.7013 0.0425833
Park 0.0352315 -0.0151497 0.0185238 1.65744 0.944041 89.6995 0.04259
Tsai-Lenz 0.0514184 -0.0291956 0.0236991 0.958984 1.89297 89.4352 0.0637015
name x y z rx ry rz distance
------ ----------- ------------ ----------- ------- -------- --------- -----------
mean 0.0368299 -0.0158447 0.0167502 0.73279 0.927639 89.9669 0.0438404
var 8.69144e-05 8.05572e-05 4.11328e-05 1.51731 0.481914 0.389663 0.000174689
std 0.00932279 0.00897536 0.00641349 1.23179 0.6942 0.62423 0.013217
Tsai-Lenz x y z rx ry rz distance
----------- ----------- ------------ ----------- ----------- ------------ ----------- -----------
point0 1.08118 -0.26596 -0.329331 1.5432 0.00335281 3.05875 1.1611
point1 1.07916 -0.25742 -0.334988 1.52213 -0.00593988 3.05615 1.15891
point2 1.08686 -0.260925 -0.335914 1.52765 -0.00494656 3.05948 1.16712
point3 1.08833 -0.256919 -0.339045 1.52961 -0.0118364 3.05914 1.16851
point4 1.07685 -0.254707 -0.324463 1.53139 0.00852579 3.05335 1.15315
mean 1.08247 -0.259186 -0.332748 1.5308 -0.00216884 3.05737 1.16176
var 1.95647e-05 1.54478e-05 2.7001e-05 4.81123e-05 5.20523e-05 5.42287e-06 3.14201e-05
std 0.0044232 0.00393036 0.00519625 0.0069363 0.00721473 0.0023287 0.00560536
複製代碼
觀察數據計算結果的標準差大小。 每次計算以後,程序都會輸出不一樣算法下標定結果點的平均數、方差、標準差三項數值。oop
因爲標定過程當中標定板是沒有發生移動的,因此咱們經過機械臂的末端位置、標定結果(手眼矩陣)、標記物在相機中的位姿便可計算出標定板在機器人基座標系下的位姿,若是標定結果準確該位姿應該是沒有變化的。測試
能夠比較最終數據的波動狀況來斷定標定結果的好壞。好比:
標定板在機械臂基座標系的位置1:
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
複製代碼
咱們能夠觀察兩次標定結果的距離的標準差,第一次的標準差小於的第二次的標準差,這表示第一次的標定結果好於第二次。
標準差越小,數據越彙集。
關注公衆號:機智人,後臺回覆棋盤格、棋盤格文件便可獲取標定用的棋盤格。
若是有不明白和有錯誤的地方能夠留言。最後歡迎你們關注、點贊、分享~
下一講給大將講一下如何將開源庫使用在JAKA機械臂上,歡迎持續關注~