Robotic Toolbox for Matlab-SeriaLink类
1、SerialLink用法
首先它是一个类表示串行连杆机械臂;其次他有两种建模方式(standard 和 modefied)
- 创建二连杆机器人
Create a 2-link robot
L(1) = Link([ 0 0 a1 pi/2], 'standard'); L(2) = Link([ 0 0 a2 0], 'standard'); twolink = SerialLink(L, 'name', 'two link');
Create a 2-link robot (most descriptive)
L(1) = Revolute('d', 0, 'a', a1, 'alpha', pi/2); L(2) = Revolute('d', 0, 'a', a2, 'alpha', 0); twolink = SerialLink(L, 'name', 'two link');
Create a 2-link robot (least descriptive)
twolink = SerialLink([0 0 a1 0; 0 0 a2 0], 'name', 'two link');
Robot objects can be concatenated in two ways
R = R1 * R2; R = SerialLink([R1 R2]);
- 函数
SerialLink.A
连杆变换矩阵
s = R.A(J, q) is an SE3 object (4x4) that transforms between link frames for the J'th joint. q is a vector (1xN) of joint variables. For:
- standard DH parameters, this is from frame {J-1} to frame {J}.
- modified DH parameters, this is from frame {J} to frame {J+1}.
s = R.A(jlist, q) as above but is a composition of link transform matrices given in the list jlist, and the joint variables are taken from the corresponding elements of q.
For example, the link transform for joint 4 is
robot.A(4, q4)
The link transform for joints 3 through 6 is
robot.A(3:6, q)
where q is 1x6 and the elements q(3) .. q(6) are used.
SerialLink.accel
机器人前向动力学
作用在关节上的力矩,及关节位置q,速度qd下的关节加速度。
qdd = R.accel(q, qd, torque) is a vector (Nx1) of joint accelerations that result from applying the actuator force/torque (1xN) to the manipulator robot R in state q (1xN) and qd (1xN), and N is the number of robot joints.
If q, qd, torque are matrices (KxN) then qdd is a matrix (KxN) where each row is the acceleration corresponding to the equivalent rows of q, qd, torque.
qdd = R.accel(x) as above but x=[q,qd,torque] (1x3N).
SerialLink.char
转换成字符
s = R.char() is a string representation of the robot's kinematic parameters, showing DH parameters, joint structure, comments, gravity vector, base and tool transform.
SerialLink.cinertia
笛卡尔惯性矩阵
m = R.cinertia(q) is the NxN Cartesian (operational space) inertia matrix which relates Cartesian force/torque to Cartesian acceleration at the joint configuration q, and N is the number of robot joints.
SerialLink.collisions
进行碰撞检测
C = R.collisions(q, model) is true if the SerialLink object R at pose q (1xN) intersects the solid model model which belongs to the class CollisionModel. The model comprises a number of geometric primitives with an associated pose.
C = R.collisions(q, model, dynmodel, tdyn) as above but also checks dynamic collision model dynmodel whose elements are at pose tdyn. tdyn is an array of transformation matrices (4x4xP), where P = length(dynmodel.primitives). The P'th plane of tdyn premultiplies the pose of the P'th primitive of dynmodel.
C = R.collisions(q, model, dynmodel) as above but assumes tdyn is the robot's tool frame.
SerialLink.coriolis
科氏力矩阵
C = R.coriolis(q, qd) is the Coriolis/centripetal matrix (NxN) for the robot in configuration q and velocity qd, where N is the number of joints. The product C*qd is the vector of joint force/torque due to velocity coupling. The diagonal elements are due to centripetal effects and the off-diagonal elements are due to Coriolis effects. This matrix is also known as the velocity coupling matrix, since it describes the disturbance forces on any joint due to velocity of all other joints.
If q and qd are matrices (KxN), each row is interpretted as a joint state vector, and the result (NxNxK) is a 3d-matrix where each plane corresponds to a row of q and qd.
C = R.coriolis( qqd) as above but the matrix qqd (1x2N) is [q qd].
Note:Computationally slow, involves N^2/2 invocations of RNE.
SerialLink.DH
将modefied DH参数转换成 standard DH参数
rmdh = R.DH() is a SerialLink object that represents the same kinematics as R but expressed using standard DH parameters.
SerialLink.display
展示参数
R.display() displays the robot parameters in human-readable form.
SerialLink.dyn
打印惯性属性
R.dyn() displays the inertial properties of the SerialLink object in a multi-line format. The properties shown are mass, centre of mass, inertia, gear ratio, motor inertia and motor friction.
R.dyn(J) as above but display parameters for joint J only.
SerialLink.edit
编辑运动学和动力学参数
R.edit displays the kinematic parameters of the robot as an editable table in a new figure.
R.edit('dyn') as above but also includes the dynamic parameters in the table.
SerialLink.fdyn
前向动力学积分,,用户可以自定义关节力矩函数
[T,q,qd] = R.fdyn(tmax, ftfun) integrates the dynamics of the robot over the time interval 0 to tmax and returns vectors of time T (Kx1), joint position q (KxN) and joint velocity qd (KxN). The initial joint position and velocity are zero. The torque applied to the joints is computed by the user-supplied control function ftfun:
TAU = FTFUN(ROBOT, T, Q, QD)
where q (1xN) and qd (1xN) are the manipulator joint coordinate and velocity state respectively, and T is the current time.
[ti,q,qd] = R.fdyn(T, ftfun, q0, qd0) as above but allows the initial joint position q0 (1xN) and velocity qd0 (1x) to be specified.
[T,q,qd] = R.fdyn(T1, ftfun, q0, qd0, ARG1, ARG2, ...) allows optional arguments to be passed through to the user-supplied control function:
TAU = FTFUN(ROBOT, T, Q, QD, ARG1, ARG2, ...)
For example, if the robot was controlled by a PD controller we can define a function to compute the control
function tau = myftfun(t, q, qd, qstar, P, D)
tau = P*(qstar-q) + D*qd;
and then integrate the robot dynamics with the control
[t,q] = robot.fdyn(10, @myftfun, qstar, P, D);
注意:
该功能在非线性关节摩擦(例如库仑摩擦)下表现不佳。 可以使用R.nofriction()方法将此摩擦设置为零。
如果未指定FTFUN或将其指定为0或[],则将零扭矩施加到机械手关节。
使用了MATLAB内置的集成函数ode45()。
SerialLink.fellipse
机械臂的力椭球
R.fellipse(q, options) displays the force ellipsoid for the robot R at pose q. The ellipsoid is centered at the tool tip position.
Options
'2d' | Ellipse for translational xy motion, for planar manipulator |
'trans' | Ellipsoid for translational motion (default) |
'rot' | Ellipsoid for rotational motion |
Display options as per plot_ellipse to control ellipsoid face and edge
color and transparency.
Example
To interactively update the force ellipsoid while using sliders to change the robot's pose:
robot.teach('callback', @(r,q) r.fellipse(q))
SerialLink.fkine
前向运动学
T = R.fkine(q, options) is the pose of the robot end-effector as an SE3 object for the joint configuration q (1xN).
If q is a matrix (KxN) the rows are interpreted as the generalized joint coordinates for a sequence of points along a trajectory. q(i,j) is the j'th joint parameter for the i'th trajectory point. In this case T is a an array of SE3 objects (K) where the subscript is the index along the path.
[T,all] = R.fkine(q) as above but all (N) is a vector of SE3 objects describing the pose of the link frames 1 to N.
Options
'deg' | Assume that revolute joint coordinates are in degrees not radians |
SerialLink.friction
关节摩擦力
tau = R.friction(qd) is the vector of joint friction forces/torques for the robot moving with joint velocities qd.
The friction model includes:
- Viscous friction which is a linear function of velocity.
- Coulomb friction which is proportional to sign(QD).
SerialLink.gencoords
符号的广义坐标向量
q = R.gencoords() is a vector (1xN) of symbols [q1 q2 ... qN].
[q,qd] = R.gencoords() as above but qd is a vector (1xN) of symbols [qd1 qd2 ... qdN].
[q,qd,qdd] = R.gencoords() as above but qdd is a vector (1xN) of symbols [qdd1 qdd2 ... qddN].
SerialLink.genforces
符号的广义力向量
q = R.genforces() is a vector (1xN) of symbols [Q1 Q2 ... QN].
SerialLink.get.config
返回关节位形的字符串
SerialLink.getpos
从图像显示中获取关节坐标
q = R.getpos() returns the joint coordinates set by the last plot or teach operation on the graphical robot.
SerialLink.gravjac
快速重力负载和雅克比
[tau,jac0] = R.gravjac(q) is the generalised joint force/torques due to gravity tau (1xN) and the manipulator Jacobian in the base frame jac0 (6xN) for robot pose q (1xN), where N is the number of robot joints.
[tau,jac0] = R.gravjac(q,grav) as above but gravitational acceleration is given explicitly by grav (3x1).
Trajectory operation
If q is MxN where N is the number of robot joints then a trajectory is assumed where each row of q corresponds to a robot configuration. tau (MxN) is the generalised joint torque, each row corresponding to an input pose, and jac0 (6xNxM) where each plane is a Jacobian corresponding to an input pose.
SerialLink.gravload
重力负载作用在关节上
taug = R.gravload(q) is the joint gravity loading (1xN) for the robot R in the joint configuration q (1xN), where N is the number of robot joints. Gravitational acceleration is a property of the robot object.
If q is a matrix (MxN) each row is interpreted as a joint configuration vector, and the result is a matrix (MxN) each row being the corresponding joint torques.
taug = R.gravload(q, grav) as above but the gravitational acceleration vector grav is given explicitly.
SerialLink.ikcon
逆运动学且带有关节约束优化
q = R.ikcon(T, options) are the joint coordinates (1xN) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and N is the number of robot joints. options is an optional list of name/value pairs than can be passed to fmincon.
[q,err] = robot.ikcon(T, options) as above but also returns err which is the scalar final value of the objective function.
[q,err,exitflag] = robot.ikcon(T, options) as above but also returns the status exitflag from fmincon.
[q,err,exitflag] = robot.ikcon(T, q0, options) as above but specify the initial joint coordinates q0 used for the minimisation.
Trajectory operation
In all cases if T is a vector of SE3 objects (1xM) or a homogeneous transform sequence (4x4xM) then returns the joint coordinates corresponding to each of the transforms in the sequence. q is MxN where N is the number of robot joints. The initial estimate of q for each time step is taken as the solution from the previous time step.
err and exitflag are also Mx1 and indicate the results of optimisation for the corresponding trajectory step.
SerialLink.ikine
逆运动学不带关节约束优化
q = R.ikine(T) are the joint coordinates (1xN) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and N is the number of robot joints.
This method can be used for robots with any number of degrees of freedom.
Options
'ilimit', L | maximum number of iterations (default 500) |
'rlimit', L | maximum number of consecutive step rejections (default 100) |
'tol', T | final error tolerance (default 1e-10) |
'lambda', L | initial value of lambda (default 0.1) |
'lambdamin', M | minimum allowable value of lambda (default 0) |
'quiet' | be quiet |
'verbose' | be verbose |
'mask', M | mask vector (6x1) that correspond to translation in X, Y and Z, and rotation about X, Y and Z respectively. |
'q0', Q | initial joint configuration (default all zeros) |
'search' | search over all configurations |
'slimit', L | maximum number of search attempts (default 100) |
'transpose', A | use Jacobian transpose with step size A, rather than Levenberg-Marquadt |
Trajectory operation
In all cases if T is a vector of SE3 objects (1xM) or a homogeneous transform sequence (4x4xM) then returns the joint coordinates corresponding to each of the transforms in the sequence. q is MxN where N is the number of robot joints. The initial estimate of q for each time step is taken as the solution from the previous time step.
Underactuated robots
For the case where the manipulator has fewer than 6 DOF the solution space has more dimensions than can be spanned by the manipulator joint coordinates.
In this case we specify the 'mask' option where the mask vector (1x6) specifies the Cartesian DOF (in the wrist coordinate frame) that will be ignored in reaching a solution. The mask vector has six elements that correspond to translation in X, Y and Z, and rotation about X, Y and Z respectively. The value should be 0 (for ignore) or 1. The number of non-zero elements should equal the number of manipulator DOF.
For example when using a 3 DOF manipulator rotation orientation might be unimportant in which case use the option: 'mask', [1 1 1 0 0 0].
For robots with 4 or 5 DOF this method is very difficult to use since orientation is specified by T in world coordinates and the achievable orientations are a function of the tool position.
SerialLink.ikine3
三轴机器人的逆运动学
q = R.ikine3(T) is the joint coordinates (1x3) corresponding to the robot end-effector pose T represented by the homogenenous transform. This is a analytic solution for a 3-axis robot (such as the first three joints of a robot like the Puma 560).
q = R.ikine3(T, config) as above but specifies the configuration of the arm in the form of a string containing one or more of the configuration codes:
'l' | arm to the left (default) |
'r' | arm to the right |
'u' | elbow up (default) |
'd' | elbow down |
SerialLink.ikine6s
分析的逆运动学
q = R.ikine(T) are the joint coordinates (1xN) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and N is the number of robot joints. This is a analytic solution for a 6-axis robot with a spherical wrist (the most common form for industrial robot arms).
If T represents a trajectory (4x4xM) then the inverse kinematics is computed for all M poses resulting in q (MxN) with each row representing the joint angles at the corresponding pose.
q = R.IKINE6S(T, config) as above but specifies the configuration of the arm in the form of a string containing one or more of the configuration codes:
'l' | arm to the left (default) |
'r' | arm to the right |
'u' | elbow up (default) |
'd' | elbow down |
'n' | wrist not flipped (default) |
'f' | wrist flipped (rotated by 180 deg) |
SerialLink.inertia
机械臂惯性矩阵
i = R.inertia(q) is the symmetric joint inertia matrix (NxN) which relates joint torque to joint acceleration for the robot at joint configuration q.
If q is a matrix (KxN), each row is interpretted as a joint state vector, and the result is a 3d-matrix (NxNxK) where each plane corresponds to the inertia for the corresponding row of q.
Notes
- The diagonal elements I(J,J) are the inertia seen by joint actuator J.
- The off-diagonal elements I(J,K) are coupling inertias that relate acceleration on joint J to force/torque on joint K.
- The diagonal terms include the motor inertia reflected through the gear ratio.
SerialLink.itorque
惯性力矩
taui = R.itorque(q, qdd) is the inertia force/torque vector (1xN) at the specified joint configuration q (1xN) and acceleration qdd (1xN), and N is the number of robot joints. taui = INERTIA(q)*qdd.
If q and qdd are matrices (KxN), each row is interpretted as a joint state vector, and the result is a matrix (KxN) where each row is the corresponding joint torques.
SerialLink.jacob0
世界坐标系的雅克比
j0 = R.jacob0(q, options) is the Jacobian matrix (6xN) for the robot in pose q (1xN), and N is the number of robot joints. The manipulator Jacobian matrix maps joint velocity to end-effector spatial velocity V = j0*QD expressed in the world-coordinate frame.
Options
'rpy' | Compute analytical Jacobian with rotation rate in terms of XYZ roll-pitch-yaw angles |
'eul' | Compute analytical Jacobian with rotation rates in terms of Euler angles |
'exp' | Compute analytical Jacobian with rotation rates in terms of exponential coordinates |
'trans' | Return translational submatrix of Jacobian |
'rot' | Return rotational submatrix of Jacobian |
SerialLink.jacob_dot
雅克比的导数
jdq = R.jacob_dot(q, qd) is the product (6x1) of the derivative of the Jacobian (in the world frame) and the joint rates.
Notes
- This term appears in the formulation for operational space control XDD = J(Q)QDD + JDOT(Q)QD
- Written as per the reference and not very efficient.
SerialLink.jacobe
雅克比在末端坐标系
je = R.jacobe(q, options) is the Jacobian matrix (6xN) for the robot in pose q, and N is the number of robot joints. The manipulator Jacobian matrix maps joint velocity to end-effector spatial velocity V = je*QD in the end-effector frame.
Options
'trans' | Return translational submatrix of Jacobian |
'rot' | Return rotational submatrix of Jacobian |
Notes
- Was joacobn() is earlier version of the Toolbox.
- This Jacobian accounts for a tool transform if one is set.
- This Jacobian is often referred to as the geometric Jacobian.
- Prior to release 10 this function was named jacobn.
SerialLink.jointdynamics
关节执行器的传递函数
tf = R.jointdynamic(q) is a vector of N continuous-time transfer function objects that represent the transfer function 1/(Js+B) for each joint based on the dynamic parameters of the robot and the configuration q (1xN). N is the number of robot joints.
% tf = R.jointdynamic(q, QD) as above but include the linearized effects of Coulomb friction when operating at joint velocity QD (1xN).
Notes
- Coulomb friction is ignoredf.
SerialLink.jtraj
Joint space trajectory
q = R.jtraj(T1, t2, k, options) is a joint space trajectory (KxN) where the joint coordinates reflect motion from end-effector pose T1 to t2 in k steps, where N is the number of robot joints. T1 and t2 are SE3 objects or homogeneous transformation matrices (4x4). The trajectory q has one row per time step, and one column per joint.
Options
'ikine', F | A handle to an inverse kinematic method, for example F = @p560.ikunc. Default is ikine6s() for a 6-axis spherical wrist, else ikine(). |
2. V-REP用法