M-File Help: Link | View code for Link |
manipulator Link class
A Link object holds all information related to a robot joint and link such as kinematics parameters, rigid-body inertial parameters, motor and transmission parameters.
Link | general constructor |
Prismatic | construct a prismatic joint+link using standard DH |
PrismaticMDH | construct a prismatic joint+link using modified DH |
Revolute | construct a revolute joint+link using standard DH |
RevoluteMDH | construct a revolute joint+link using modified DH |
display | print the link parameters in human readable form |
dyn | display link dynamic parameters |
type | joint type: 'R' or 'P' |
char | convert to string |
A | link transform matrix |
friction | friction force |
nofriction | Link object with friction parameters set to zero% |
islimit | test if joint exceeds soft limit |
isrevolute | test if joint is revolute |
isprismatic | test if joint is prismatic |
issym | test if joint+link has symbolic parameters |
+ | concatenate links, result is a SerialLink object |
theta | kinematic: joint angle |
d | kinematic: link offset |
a | kinematic: link length |
alpha | kinematic: link twist |
jointtype | kinematic: 'R' if revolute, 'P' if prismatic |
mdh | kinematic: 0 if standard D&H, else 1 |
offset | kinematic: joint variable offset |
qlim | kinematic: joint variable limits [min max] |
m | dynamic: link mass |
r | dynamic: link COG wrt link coordinate frame 3x1 |
I | dynamic: link inertia matrix, symmetric 3x3, about link COG. |
B | dynamic: link viscous friction (motor referred) |
Tc | dynamic: link Coulomb friction |
G | actuator: gear ratio |
Jm | actuator: motor inertia (motor referred) |
L = Link([0 1.2 0.3 pi/2]); L = Link('revolute', 'd', 1.2, 'a', 0.3, 'alpha', pi/2); L = Revolute('d', 1.2, 'a', 0.3, 'alpha', pi/2);
Link, Revolute, Prismatic, SerialLink, RevoluteMDH, PrismaticMDH
Create robot link object
This the class constructor which has several call signatures.
L = Link() is a Link object with default parameters.
L = Link(lnk) is a Link object that is a deep copy of the link object lnk and has type Link, even if lnk is a subclass.
L = Link(options) is a link object with the kinematic and dynamic parameters specified by the key/value pairs.
'theta', TH | joint angle, if not specified joint is revolute |
'd', D | joint extension, if not specified joint is prismatic |
'a', A | joint offset (default 0) |
'alpha', A | joint twist (default 0) |
'standard' | defined using standard D&H parameters (default). |
'modified' | defined using modified D&H parameters. |
'offset', O | joint variable offset (default 0) |
'qlim', L | joint limit (default []) |
'I', I | link inertia matrix (3x1, 6x1 or 3x3) |
'r', R | link centre of gravity (3x1) |
'm', M | link mass (1x1) |
'G', G | motor gear ratio (default 1) |
'B', B | joint friction, motor referenced (default 0) |
'Jm', J | motor inertia, motor referenced (default 0) |
'Tc', T | Coulomb friction, motor referenced (1x1 or 2x1), (default [0 0]) |
'revolute' | for a revolute joint (default) |
'prismatic' | for a prismatic joint 'p' |
'standard' | for standard D&H parameters (default). |
'modified' | for modified D&H parameters. |
'sym' | consider all parameter values as symbolic not numeric |
L = Link(dh, options) is a link object using the specified kinematic convention and with parameters:
'standard' | for standard D&H parameters (default). |
'modified' | for modified D&H parameters. |
'revolute' | for a revolute joint, can be abbreviated to 'r' (default) |
'prismatic' | for a prismatic joint, can be abbreviated to 'p' |
A standard Denavit-Hartenberg link
L3 = Link('d', 0.15005, 'a', 0.0203, 'alpha', -pi/2);
since 'theta' is not specified the joint is assumed to be revolute, and since the kinematic convention is not specified it is assumed 'standard'.
Using the old syntax
L3 = Link([ 0, 0.15005, 0.0203, -pi/2], 'standard');
the flag 'standard' is not strictly necessary but adds clarity. Only 4 parameters are specified so sigma is assumed to be zero, ie. the joint is revolute.
L3 = Link([ 0, 0.15005, 0.0203, -pi/2, 0], 'standard');
the flag 'standard' is not strictly necessary but adds clarity. 5 parameters are specified and sigma is set to zero, ie. the joint is revolute.
L3 = Link([ 0, 0.15005, 0.0203, -pi/2, 1], 'standard');
the flag 'standard' is not strictly necessary but adds clarity. 5 parameters are specified and sigma is set to one, ie. the joint is prismatic.
For a modified Denavit-Hartenberg revolute joint
L3 = Link([ 0, 0.15005, 0.0203, -pi/2, 0], 'modified');
Revolute, Prismatic, RevoluteMDH, PrismaticMDH
Link transform matrix
T = L.A(q) is an SE3 object representing the transformation between link frames when the link variable q which is either the Denavit-Hartenberg parameter THETA (revolute) or D (prismatic). For:
Convert to string
s = L.char() is a string showing link parameters in a compact single line format. If L is a vector of Link objects return a string with one line per Link.
Display parameters
L.display() displays the link parameters in compact single line format. If L is a vector of Link objects displays one line per element.
Link.char, Link.dyn, SerialLink.showlink
Show inertial properties of link
L.dyn() displays the inertial properties of the link object in a multi-line format. The properties shown are mass, centre of mass, inertia, friction, gear ratio and motor properties.
If L is a vector of Link objects show properties for each link.
Joint friction force
f = L.friction(qd) is the joint friction force/torque (1xN) for joint velocity qd (1xN). The friction model includes:
Concatenate link objects
[L1 L2] is a vector that contains deep copies of the Link class objects L1 and L2.
Test joint limits
L.islimit(q) is true (1) if q is outside the soft limits set for this joint.
Test if joint is prismatic
L.isprismatic() is true (1) if joint is prismatic.
Test if joint is revolute
L.isrevolute() is true (1) if joint is revolute.
Check if link is a symbolic model
res = L.issym() is true if the Link L has any symbolic parameters.
Remove friction
ln = L.nofriction() is a link object with the same parameters as L except nonlinear (Coulomb) friction parameter is zero.
ln = L.nofriction('all') as above except that viscous and Coulomb friction are set to zero.
ln = L.nofriction('coulomb') as above except that Coulomb friction is set to zero.
ln = L.nofriction('viscous') as above except that viscous friction is set to zero.
Link.friction, SerialLink.nofriction, SerialLink.fdyn
Concatenate link objects into a robot
L1+L2 is a SerialLink object formed from deep copies of the Link class objects L1 and L2.
SerialLink, SerialLink.plus, Link.horzcat
Set link inertia
L.I = [Ixx Iyy Izz] sets link inertia to a diagonal matrix.
L.I = [Ixx Iyy Izz Ixy Iyz Ixz] sets link inertia to a symmetric matrix with specified inertia and product of intertia elements.
L.I = M set Link inertia matrix to M (3x3) which must be symmetric.
Set centre of gravity
L.r = R sets the link centre of gravity (COG) to R (3-vector).
Set Coulomb friction
L.Tc = F sets Coulomb friction parameters to [F -F], for a symmetric Coulomb friction model.
L.Tc = [FP FM] sets Coulomb friction to [FP FM], for an asymmetric Coulomb friction model. FP>0 and FM<0. FP is applied for a positive joint velocity and FM for a negative joint velocity.
Convert link parameters to symbolic type
LS = L.sym is a Link object in which all the parameters are symbolic ('sym') type.
Joint type
c = L.type() is a character 'R' or 'P' depending on whether joint is revolute or prismatic respectively. If L is a vector of Link objects return an array of characters in joint order.
© 1990-2014 Peter Corke.