Calibration technology
In common robot vision servoing systems, to achieve the conversion between pixel coordinates and actual coordinates, calibration is the first step. For vision servo control, this calibration includes not only camera calibration but also hand-eye calibration of the robot system. Taking a common welding robot system as an example, there are two configurations, as follows:
That is: the camera is fixed to the robotic arm and the camera is fixed to the external scene;
This article focuses on the former configuration: the camera is fixed to the robotic arm.
1. Camera calibration technology
(1) Theoretical part:
Using Zhang Zhengyou's chessboard calibration method as the camera calibration method, since the camera calibration results will be used in the subsequent hand-eye calibration, the following must be observed when taking pictures of the chessboard from different positions: the calibration board must be fixed in one position and the hand-eye combination must change its posture to take pictures.
The purpose of camera calibration is to obtain pairwise transformation matrices between two coordinate systems: T1 and T2.
1) Obtain the transformation matrix T1 between the image pixel coordinate system P and the camera coordinate system C. More precisely, it should be the transformation matrix from the camera coordinate system to the image pixel coordinate system. This can be represented as:
P=T1*C;
Explanation: T1 in the camera calibration results is the intrinsic parameter matrix 3x3;
2) Obtain the transformation matrix T2 between the camera coordinate system C and the world coordinate system G established on the chessboard. More precisely, it should be the transformation matrix from coordinate system G to the camera coordinate system. This can be represented as:
C = T² * G;
Explanation: In the camera calibration results, T2 is the extrinsic parameter matrix 4x4, which is composed of the rotation matrix r and the translation vector t [ t r; 0 0 0 1];
(2) Method:
There are two options for camera calibration: OpenCV or Matlab calibration toolbox;
It is recommended to select MATLAB application – Image Processing and Computer Vision – Camera Calibration or , and directly import the captured images. However, please note that the intrinsic parameter matrix, extrinsic rotation matrix, and extrinsic translation vector obtained using the MATLAB calibration toolbox must be transposed to obtain the correct results.
As shown in the figure below, the red boxes obtained from MATLAB calibration contain, in order, the extrinsic translation vector, the intrinsic matrix, and the extrinsic rotation matrix. All of these need to be transposed before they can be used in the formula calculations presented in this article.
2. Hand-eye calibration technology
(1) Theoretical part:
The purpose of hand-eye calibration is to obtain the transformation matrix T3 between the camera coordinate system C and the robot (or tool) coordinate system H. More precisely, it should be the transformation matrix from the robot coordinate system to the camera coordinate system. This can be represented as:
C = T3 * H;
Explanation: T3 needs to be obtained using the formula CX=XD; in practice, knowing C and D separately, there are infinitely many solutions for X. Therefore, to achieve a unique solution, we need at least two sets of C and D, that is, at least three camera calibration results.
The method for finding C is as follows:
C is the transformation matrix between the two camera coordinate systems. It can be calculated using the two camera calibration extrinsic parameters A and B obtained from any two calibration images above, according to the formula C = A * inv(B). Assuming that the extrinsic parameter calibration results of the three calibration images above are T21, T22, and T23, then two C matrices can be obtained:
C1 = T21 * inv(T22);
C2 = T22 * inv(T23);
The method for finding D is as follows:
D is the transformation matrix between the two robot coordinate systems. Assuming the description matrices of the robot coordinate systems corresponding to the three calibration images in the above camera calibration, in the base coordinate system (which could also be the workpiece coordinate system or other fixed reference coordinate system), are H1, H2, and H3 respectively (H needs to be read from the robot controller or teach pendant), then we can obtain two D matrices:
D1 = inv(H1) * H2;
D2 = inv(H2) * H3;
Substituting C and D into CX=XD, we can obtain the unique solution X, thus T3=X;
Note: H1, H2, and H3 above are the robot arm coordinate system description matrices corresponding to each calibration image, which precisely illustrates the correctness of the so-called "fixed calibration plate, hand-eye movement" in camera calibration. If the hand and eye do not move, and the orientation of the calibration plate is changed for shooting, then the value of H will be the same.
(2) Method:
1) Based on the camera calibration and the known camera extrinsic parameter matrices T21, T22, and T23, it is also necessary to read the corresponding robot hand (or tool) coordinate systems H1, H2, and H3 from the robot controller. The coordinate system description matrix in the controller is not directly read; it exists in the form of translation vectors and Euler angles (or quaternions), as follows:
Translation vector + Euler angles mode:
Translation vector + quaternion pattern:
Choose any of the modes and then convert it into a description matrix.
After completing the above steps, we have obtained three extrinsic parameter matrices (again, if using the MATLAB calibration toolbox for camera calibration, the obtained extrinsic parameter rotation matrix and translation vector must first be transposed, i.e., R=r', T=t', and then the extrinsic parameter matrix EX=[RT; 0 0 0 1]) and three robot coordinate system matrices. Therefore, we can combine the three two-dimensional matrices into a single three-dimensional matrix. The MATLAB command is as follows:
C_ext=cat(3, C_ext1, C_ext2, C_ext3);
H = cat(3, H1, H2, H3)
Finally, C_ext and H are substituted as parameters into the following MATLAB function:
function Tch = GetCamera2HandMatrix(C_ext,H)
% The following variables:
% C_ext is the extrinsic parameter matrix of the camera at 3 positions: 3x4x4
H1, H2, and H3 are the pose matrices of the robot's coordinate system at three positions: 3x4x4
% Tcg -- The pose and position transformation matrix of the robot's coordinate system (or tool coordinate system) in the camera coordinate system. % C1, D1, C2, D2, R, w, q, kc1, kc2, kc3, kd1, kd2, kd3, a, b, c, d, h, y are all temporary variables. C1=C_ext(:,:,1)*inv(C_ext(:,:,2))
C2=C_ext(:,:,2)*inv(C_ext(:,:,3))
D1=inv(H(:,:,1))*H(:,:,2)
D2=inv(H(:,:,2))*H(:,:,3)
R=C1(1:3,1:3);
q=acos((trace(R)-1)/2);
w(1,1)=q/(2*sin(q))*(R(3,2)-R(2,3));
w(2,1)=q/(2*sin(q))*(R(1,3)-R(3,1));
w(3,1)=q/(2*sin(q))*(R(2,1)-R(1,2));
kc1=w;
R=C2(1:3,1:3);
q=acos((trace(R)-1)/2);
w(1,1)=q/(2*sin(q))*(R(3,2)-R(2,3));
w(2,1)=q/(2*sin(q))*(R(1,3)-R(3,1));
w(3,1)=q/(2*sin(q))*(R(2,1)-R(1,2));
kc2=w;
R=D1(1:3,1:3);
q=acos((trace(R)-1)/2);
w(1,1)=q/(2*sin(q))*(R(3,2)-R(2,3));
w(2,1)=q/(2*sin(q))*(R(1,3)-R(3,1));
w(3,1)=q/(2*sin(q))*(R(2,1)-R(1,2));
kd1=w;
R=D2(1:3,1:3);
q=acos((trace(R)-1)/2);
w(1,1)=q/(2*sin(q))*(R(3,2)-R(2,3));
w(2,1)=q/(2*sin(q))*(R(1,3)-R(3,1));
w(3,1)=q/(2*sin(q))*(R(2,1)-R(1,2));
kd2=w;
kc3 = cross(kc1, kc2);
kd3 = cross(kd1, kd2);
a=[kc1 kc2 kc3];
b=[kd1 kd2 kd3];
R = a * inv(b); % Get the rotation relation matrix
tc1=C1(1:3,4);
tc2=C2(1:3,4);
td1=D1(1:3,4);
td2=D2(1:3,4);
c = R * td1 - tc1;
d = R * td² - tc²;
a=C1(1:3,1:3)-[1 0 0;0 1 0;0 0 1];
b=C2(1:3,1:3)-[1 0 0;0 1 0;0 0 1];
h=[a;b];
y=[c;d];
t=inv(h'*h)*h'*y; % Obtain the translation matrix
Tch=[R t;0 0 0 1]; %Get the final result end 3. Achieve monocular positioning of targets at fixed altitudes based on calibration results.
(1) Theoretical part:
From the above two calibrations 1 and 2, we have obtained:
The transformation matrix Tpc from camera coordinate system C to pixel coordinate system P (i.e., the intrinsic parameter matrix, which needs to be transposed after MATLAB calibration).
The transformation matrix Tch from the robot arm (or tool) coordinate system H to the camera coordinate system C;
The transformation matrix Tbh read from the controller is the transformation matrix Tbh from the robot (or tool) coordinate system H to the base coordinate system B (this can be set in the controller as either the base coordinate system or the workpiece coordinate system; this article uses the base coordinate system).
Given that the target height is fixed and denoted by z;
Therefore, the transformation matrix from the base coordinate system to the pixel coordinate system is: Gpb = Tpc * Tch * inv(Tbh);
Based on Gpb and z, the transformation process shown in the figure below can be obtained. After decomposition, the actual coordinates (x, y, z) can be obtained from the pixel coordinates (u, v):
Note that for Tpc, a column of all zeros should be added at the end of the intrinsic parameter matrix to make it a 3x4 matrix, as follows:
(2) Code implementation:
function P= GetObjectLocation( u,v,Gtb)
% The parameters (u,v) are the pixel coordinates of the target in the image. % The parameter Gtb is the description matrix of the tool in the robot's base coordinates (that is, the transformation matrix from the tool coordinate system to the base coordinate system).
%Internal parameter matrix Kl=[ 1851 9.7 550.5 0;
0 1844.4 299.7 0;
0 0 1.0 0];
%Camera and tool relationship matrix Gctl= [-0.9620 -0.2974 0.0156 -2.6405;
0.3266 -0.9552 0.0056 59.7141;
0.0130 0.0003 1.0161 145.3381;
0 0 0 1.0000];
G = inv(Gtb);
z=10; %Specifies the height of the object M=Kl*Gctl*G;
Ml=[u*M(3,1)-M(1,1) u*M(3,2)-M(1,2) ; v*M(3,1)-M(2,1) v*M(3,2)-M(2,2)];
Mr=[M(1,4)-u*M(3,4)-(u*M(3,3)-M(1,3))*z; M(2,4)-v*M(3,4)-(v*M(3,3)-M(2,3))*z];
P = inv(Ml) * Mr; % Get the position of the object end