[Matlab six-degree-of-freedom robot] Define standard and improved DH parameters to establish a robot model (with MATLAB modeling code)

recent update

【Summary】

Summary of [Matlab Six Degrees of Freedom Robot] Series Articles \fcolorbox{green}{aqua}{[Matlab Six Degrees of Freedom Robot] Series Article Summary }[ M a t l a b six degrees of freedom robot ] series of articles   summary

【Main line】

Kinematics\color{red}Kinematicskinematics

  1. Define standard and improved DH parameters, and establish a robot model.
  2. Correct solution of kinematics
  3. Construction of Robot Workspace Based on Monte Carlo Method

Dynamics\color{red}dynamicsKinetics
(to be added)

【Supplementary explanation】

  1. Understanding of Flexible Workspaces and Accessible Workspaces
  2. Detailed establishment steps of modified DH parameters (modified Denavit-Hartenberg)
  3. Questions about parameterization of rotation (Euler angles, attitude angles, quaternions)
  4. The Explanation of Double Variable Function atan2(x,y)
  5. Some Problems Concerning Inverse Solution of Robot Kinematics
This article mainly describes how to understand and design the DH parameters of a six-axis robot in Matlab, how to build a six-degree-of-freedom robot model, and then solve the positive and negative solutions of the robot.

foreword

1. Matlab robot toolbox

Since we need to get in touch with the robot toolbox on Matlab, we first upload the official website for downloading the toolbox. You don’t need credits, you can download it directly from the official website, so you don’t have to worry about problems. https://petercorke.com/resources/downloads/Related
resources: If found unablenormalLog in to this website, and you can download the robot toolbox compression package through this resource: Matlab robot toolbox-robot-10.3.1 and related examples .
AltThe specific installation method has been explained very clearly by a friend: Matlab robot toolbox

2. Research object - six degrees of freedom robot

The parameters of each connecting rod of the robot are called out, and the DH parameters of the robot can be obtained according to the length and structure of each connecting rod.

Alt
With the development of artificial intelligence, robots are constantly changing and appearing in people's eyes, some appear as service robots in restaurants, and some appear as smart cars. All of them show the multi-purpose of the robot and its multi-function, and the most typical and basic one is the industrial robot.


text

1. DH parameters (Denavit–Hartenberg parameters)

An important characteristic parameter of the robotic arm is the DH parameter.insert image description here

Coordinate system establishment steps:

  1. Determine the Z-axis If the joint is rotating, the Z-axis points to the positive direction according to the right-hand rule, and the joint rotation angle θ is the joint variable. If the joint is moving, the Z axis is set in the positive direction along the linear motion direction, and the link offset d is the joint variable.
  2. Determine the X-axis Situation 1: The Z-axes of the two joints are neither parallel nor intersecting, that is, when they form straight lines with different planes. Then take the direction of the common vertical line of the two Z axes as the direction of the X axis. Case 2: The Z axes of the two joints are parallel. At this time, there are countless common perpendicular lines between the two Z axes, and one common perpendicular line collinear with the common perpendicular line of the previous joint can be selected.
    Case 3: The Z axes of the two joints intersect. Then take the cross product direction of the two Z axes as the X axis (cross product: vector product)
  3. Determining the Y-axis The direction of the Y-axis is determined by the right-hand rule. The thumb points to the direction of the Z axis, the direction of the x axis is the direction, and the direction of the 90° counterclockwise rotation is the direction of the y axis.

For the standard type and the improved type, the difference is that the fixed coordinate system is different and the order of performing the transformation is different.

1. Standard DH parameters (STD)

  1. For the standard type, the direction of the X axis is the cross product direction of the current Z axis and the Z axis of the previous joint (that is, the Z i-1 axis). The right hand rule: from the Z i-1 axis to the Z axis, the direction of the thumb is the X axis direction. A simple method can also be used, pointing from the Z i-1 axis to the Z axis, and the direction of the common vertical line is the direction of the X axis. Attach a more intuitive video: the most intuitive explanation of DH parameters in robotics is necessary for getting started with robots
  2. Modeling steps:
    (1) Rotate θ i around the zi − 1 axis so that xi − 1 and xi are parallel; (1) Rotate θ_i around the z_{i-1} axis so that x_{i-1} and x_{i} are parallel;( 1 ) around zi1Axis rotation θi, such that xi1and xiparallel ;
    ( 2 ) Translate di along the zi − 1 axis so that xi − 1 and xi coincide; (2) Translate d_{i} along the z_{i-1} axis so that x_{i-1} and x_{i} coincide;( 2 ) along zi1Axis translation di, such that xi1and xiCoincident ;
    ( 3 ) Translate ai along the xi axis, so that zi − 1 and zi coincide; (3) Translate a_{i} along the x_{i} axis, so that z_{i-1} and z_{i} coincide;( 3 ) along xiAxis translation ai, so that zi1and ziCoincidence ;
    ( 4 ) Rotate α i around the xi axis so that zi − 1 and zi are collinear; (4) Rotate α_{i} around the x_{i} axis so that z_{i-1} and z_{i} are collinear;( 4 ) Around xiAxis rotation αi, so that zi1and ziCollinear ; _
  3. When the STD-DH method is transformed, the order of multiplication of the four parameters is θ θθ d d d a a aa aa
  4. Get the rotation matrix R ot ( zi − 1 , θ i ) Rot(z_{i-1},θ_i) through each step of rotation and translation
    Rot(zi1,ii) = [ c o s θ i − s i n θ i 0 0 s i n θ i c o s θ i 0 0 0 0 1 0 0 0 0 1 ] \left[ \begin{matrix} cosθ_i & -sinθ_i & 0&0 \\ sinθ_i & cosθ_i & 0 &0\\ 0 & 0& 1& 0\\ 0 & 0& 0& 1 \end{matrix} \right] cosθisinθi00sinθicosθi0000100001

T r a n s ( z i − 1 , d i ) = Trans(z_{i-1},d_i)= Trans(zi1di)= [ 1 0 0 0 0 1 0 0 0 0 1 d i 0 0 0 1 ] \left[ \begin{matrix} 1&0&0&0 \\ 0&1&0 &0\\ 0&0&1&d_{i} \\ 0&0&0&1 \end{matrix} \right] 10000100001000di1

T r a n s ( x i , a i ) = Trans(x_i,a_i)= Trans(xiai)= [ 1 0 0 a i 0 1 0 0 0 0 1 0 0 0 0 1 ] \left[ \begin{matrix} 1&0&0&a_{i} \\ 0&1&0 &0\\ 0&0&1&0 \\ 0&0&0&1 \end{matrix} \right] 100001000010ai001

R o t ( x i , α i ) = Rot(x_i,α_i)= Rot(xi, ai)= [ 1 0 0 0 0 cos α i − sin α i 0 0 sin α icos α i 0 0 0 0 1 ] \left[ \begin{matrix} 1& 0 & 0&0 \\ 0& cosα_i & -sinα_i &0\\ 0& sinα_i & cosα_i& 0\\ 0& 0& 0& 1 \end{matrix } \right]10000c o s αiI n α _i00- s i n αic o s αi00001

T i − 1 T i = Rot ( zi − 1 , θ i ) × T rans ( zi − 1 , di ) × T rans ( xi , ai ) × Rot ( xi , α i ) T i − 1 T_i = Rot(z_{i-1}, θ_i) × Trans(z_{i-1}, d_i) × Trans(x_i, a_i) × Rot(x_i, α_i)The transformation matrix can be obtainedi1Ti=Rot(zi1,ii)×Trans(zi1di)×Trans(xiai)×Rot(xi, ai)

i − 1 T i = ^{i-1}T_i = i1Ti= [ c o s θ i − s i n θ i c o s α i s i n θ i s i n α i a i c o s θ i s i n θ i c o s θ i c o s α i − c o s θ i s i n α i a i s i n θ i 0 s i n α i c o s α i d i 0 0 0 1 ] \left[ \begin{matrix} cosθ_i&-sinθ_icosα_i&sinθ_isinα_i&a_{i}cosθ_i \\ sinθ_i&cosθ_icosα_i&-cosθ_isinα_i&a_{i}sinθ_i\\ 0&sinα_i&cosα_i&d_{i} \\ 0&0&0&1 \end{matrix} \right] cosθisinθi00sinθic o s αicosθic o s αiI n α _i0sinθiI n α _icosθiI n α _ic o s αi0aicosθiaisinθidi1

2. Improved DH parameters (MOD)

  1. For the improved version, XXThe direction of the X axis is based on the current Z axis andthe ZZofthe next jointZ axis (that is,Z i + 1 Z_{i+1}Zi+1axis), using the right-hand rule: from the Z axis to Z i + 1 Z_{i+1}Zi+1Axis, thumb direction is XXX- axis direction. Specifically how to build see the above build steps, aboutXXThe three cases determined by the X axis.
  2. Modeling steps:
    (1) Rotate α i around the xi axis so that zi and zi + 1 are collinear; (1) Rotate α_{i} around the x_{i} axis so that z_{i} and z_{i+1} are collinear;( 1 ) around xiAxis rotation αi, so that ziand zi+1Collinear ; (2) Translate
    ai along the xi axis so that zi and zi + 1 coincide (2) Translate a_{i} along the x_{i} axis so that z_{i} and z_{i+1} coincide( 2 ) along xiAxis translation ai, so that ziand zi+1Coincidence
    ( 3 ) Rotate θ i around the zi axis so that xi − 1 and xi are collinear; (3) Rotate θ_i around the z_{i} axis so that x_{i-1} and x_{i} are collinear;( 3 ) around ziAxis rotation θi, such that xi1and xiCollinear ; ( 4 ) Translate
    di along the zi axis so that xi − 1 and xi coincide; (4) Translate d_{i} along the z_{i} axis so that x_{i-1} and x_{i} coincide;( 4 ) along ziAxis translation di, such that xi1and xioverlap ;
  3. When the MOD-DH method is transformed, the order of multiplication of the four parameters is α αα a a aθ θθ d d d
  4. T i − 1 T i = Rot ( xi , α i − 1 ) × T rans ( xi , ai − 1 ) × R ot
    ( zi , θ i ) × T rans ( zi , di ) ^{i-1} T_i = Rot(x_{i}, α_{i-1}) × Trans(x_{i}, a_{i -1})×Rot(z_{i},θ_i)×Trans(z_{i},d_i)i1Ti=Rot(xi, ai1)×Trans(xiai1)×Rot(zi,ii)×Trans(zidi)

i − 1 T i = ^{i-1}T_i = i1Ti= [ c o s θ i − s i n θ i 0 a i − 1 s i n θ i c o s α i − 1 c o s θ i c o s α i − 1 − s i n α i − 1 − s i n α i − 1 d i s i n θ i s i n α i − 1 c o s θ i s i n α i − 1 c o s α i − 1 c o s α i − 1 d i 0 0 0 1 ] \left[ \begin{matrix} cosθ_i&-sinθ_i&0&a_{i-1} \\ sinθ_icosα_{i-1}&cosθ_icosα_{i-1}&-sinα_{i-1}&-sinα_{i-1}d_{i} \\ sinθ_isinα_{i-1}&cosθ_isinα_{i-1}&cosα_{i-1}&cosα_{i-1}d_{i} \\ 0&0&0&1 \end{matrix} \right] cosθisinθic o s αi1sinθiI n α _i10sinθicosθic o s αi1cosθiI n α _i100- s i n αi1c o s αi10ai1- s i n αi1dic o s αi1di1

DH parameters are the only way to study various types of robots. Only by being familiar with the DH parameters of building robots can we better solve the positive and negative solutions for robots.

2. Link function and SerialLink function

link functionContains all information related to robot joints and links, such as kinematic parameters, rigid body inertia parameters, motor and transmission parameters.
The various parameters of the Link function are as follows:

Kinematic parameters meaning
theta joint angle 关节转角
d link offset 连杆偏移
a link length 连杆长度
alpha link twist 连杆扭角
jointtype ‘R’ if revolute, ‘P’ if prismatic 旋转关节为R,移动关节为P
mdh 0 if standard D&H, else 1 标准型为0,改进型为1
offset joint variable offset 关节变量偏移
floor joint variable limits [min max] 关节变量极限[min max]
Kinetic parameters meaning
m link mass 连杆质量
r link COG wrt link coordinate frame 3x1 连杆相对于坐标系的质心位置 3x1位置矩阵
I link inertia matrix, symmetric 3x3, about link COG.连杆重心相对于坐标系的惯性矩阵 3x3旋转矩阵
B link viscous friction (motor referred) 连杆粘性摩擦力(以电机为基准)
Tc link Coulomb friction 连杆库仑摩擦力
G gear ratio 齿轮比(传动比)
Jm motor inertia (motor referred)电机惯量(以电机为基准)

For the situation where it is only necessary to establish the robot model without considering the dynamic parameters of the robot, then only theta、d、a、alpha和offseta few parameters need to be used.


Next, use the Link function to model the DH parameter table, and use the SerialLink function to connect L1 L2 L3 L4 L5 L6the connecting rods.
For the Link function, whether it is a standard type or an improved type, the order of parameters is as follows:Joint rotation angle, link offset, link length, link torsion angle.

1. Use standard DH parameters to build a robot model

%% STD-DH参数
%定义连杆的D-H参数
%连杆偏移
d1 = 398;
d2 = -0.299;
d3 = 0;
d4 = 556.925;
d5 = 0;
d6 = 165;
%连杆长度
a1 = 168.3;
a2 = 650.979;
a3 = 156.240;
a4 = 0;
a5 = 0;
a6 = 0;
%连杆扭角
alpha1 = pi/2;
alpha2 = 0;
alpha3 = pi/2;
alpha4 = -pi/2;
alpha5 = pi/2;
alpha6 = 0;
%建立机器人模型
%       theta  d        a        alpha    
L1=Link([0     d1       a1       alpha1]);
L2=Link([0     d2       a2       alpha2]);L2.offset = pi/2;
L3=Link([0     d3       a3       alpha3]);
L4=Link([0     d4       a4       alpha4]);
L5=Link([0     d5       a5       alpha5]);
L6=Link([0     d6       a6       alpha6]);
%限制机器人的关节空间
L1.qlim = [(-165/180)*pi,(165/180)*pi];
L2.qlim = [(-95/180)*pi, (70/180)*pi];
L3.qlim = [(-85/180)*pi, (95/180)*pi];
L4.qlim = [(-180/180)*pi,(180/180)*pi];
L5.qlim = [(-115/180)*pi,(115/180)*pi];
L6.qlim = [(-360/180)*pi,(360/180)*pi];
%连接连杆,机器人取名为myrobot
robot=SerialLink([L1 L2 L3 L4 L5 L6],'name','myrobot');
robot.plot([0,0,0,0,0,0]);%输出机器人模型,后面的六个角为输出时的theta姿态
robot.display();%打印出机器人D-H参数表
robot.teach;%展示机器人模型
hold on;

2. Use the improved DH parameters to build a robot model

Where 'modified' means that the robot uses the modified DH parameter table to build the model.

%% MOD-DH参数
%定义连杆的D-H参数
%连杆偏移
d1 = 398;
d2 = -0.299;
d3 = 0;
d4 = 556.925;
d5 = 0;
d6 = 165;
%连杆长度
a1 = 0;
a2 = 168.3;
a3 = 650.979;
a4 = 156.240;
a5 = 0;
a6 = 0;
%连杆扭角
alpha1 = 0;
alpha2 = pi/2;
alpha3 = 0;
alpha4 = pi/2;
alpha5 = -pi/2;
alpha6 = pi/2;
%建立机器人模型
%       theta  d        a        alpha     
L1=Link([0     d1       a1       alpha1     ],'modified');
L2=Link([0     d2       a2       alpha2     ],'modified');L2.offset = pi/2;
L3=Link([0     d3       a3       alpha3     ],'modified');
L4=Link([0     d4       a4       alpha4     ],'modified');
L5=Link([0     d5       a5       alpha5     ],'modified');
L6=Link([0     d6       a6       alpha6     ],'modified');
%限制机器人的关节空间
L1.qlim = [(-165/180)*pi,(165/180)*pi];
L2.qlim = [(-95/180)*pi, (70/180)*pi];
L3.qlim = [(-85/180)*pi, (95/180)*pi];
L4.qlim = [(-180/180)*pi,(180/180)*pi];
L5.qlim = [(-115/180)*pi,(115/180)*pi];
L6.qlim = [(-360/180)*pi,(360/180)*pi];
%连接连杆,机器人取名为myrobot
robot=SerialLink([L1 L2 L3 L4 L5 L6],'name','myrobot');
robot.plot([0,0,0,0,0,0]);%输出机器人模型,后面的六个角为输出时的theta姿态
robot.display();%打印出机器人D-H参数表
robot.teach;%展示机器人模型
hold on;

annotation:L2.offset = pi/2It means that the second axis has a 90-degree joint offset relative to the first axis, that is, in the initial state, the link 2 has a joint offset for the link 1.

Next, look at the difference between adding joint offsets and not adding them:
Adding joint offsets Add joint offset
does not add joint offsetsinsert image description here

It can be seen that whether the joint offset is added or not is quite different for the end position of the robot.


References

  1. Matlab Robot Toolbox (1) - Establishment, Drawing and Forward and Inverse Kinematics of Robots
  2. Matlab Robot Toolbox
  3. The difference between standard DH and improved DH
  4. Standard DH Modeling and Improved DH Modeling
  5. Talking about Standard DH (SDH) and Modified DH (MDH)
  6. Denavit–Hartenberg parameters

Guess you like

Origin blog.csdn.net/AlbertDS/article/details/109378377