Link

Robot manipulator Link class

A Link object holds all information related to a robot link such as kinematics parameters, rigid-body inertial parameters, motor and transmission parameters.

Methods

A link transform matrix
RP joint type: 'R' or 'P'
friction friction force
nofriction Link object with friction parameters set to zero
dyn display link dynamic parameters
islimit test if joint exceeds soft limit
isrevolute test if joint is revolute
isprismatic test if joint is prismatic
display print the link parameters in human readable form
char convert to string

Properties (read/write)

theta kinematic: joint angle
d kinematic: link offset
a kinematic: link length
alpha kinematic: link twist
sigma kinematic: 0 if revolute, 1 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)

Examples

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);

Notes

References

See also

Link, Revolute, Prismatic, SerialLink, RevoluteMDH, PrismaticMDH


Link.Link

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.

L = Link(options) is a link object with the kinematic and dynamic parameters specified by the key/value pairs.

Options

'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

Old syntax

L = Link(dh, options) is a link object using the specified kinematic convention and with parameters:

Options

'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'

Examples

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');

Notes

See also

Revolute, Prismatic


Link.A

Link transform matrix

T = L.A(q) is the link homogeneous transformation matrix (4x4) corresponding to the link variable q which is either the Denavit-Hartenberg parameter THETA (revolute) or D (prismatic).

Notes


Link.char

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.

See also

Link.display


Link.display

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.

Notes

See also

Link.char, Link.dyn, SerialLink.showlink


Link.dyn

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.

See also

SerialLink.dyn


Link.friction

Joint friction force

f = L.friction(qd) is the joint friction force/torque for link velocity qd.

Notes


Link.islimit

Test joint limits

L.islimit(q) is true (1) if q is outside the soft limits set for this joint.

Note


Link.isprismatic

Test if joint is prismatic

L.isprismatic() is true (1) if joint is prismatic.

See also

Link.isrevolute


Link.isrevolute

Test if joint is revolute

L.isrevolute() is true (1) if joint is revolute.

See also

Link.isprismatic


Link.issym

Check if link is a symbolic model

res = L.issym() is true if the Link L has symbolic parameters.


Link.nofriction

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.

Notes

See also

SerialLink.nofriction, SerialLink.fdyn


Link.RP

Joint type

c = L.RP() is a character 'R' or 'P' depending on whether joint is revolute or prismatic respectively. If L is a vector of Link objects return a string of characters in joint order.


Link.set.I

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.


Link.set.r

Set centre of gravity

L.r = R sets the link centre of gravity (COG) to R (3-vector).


Link.set.Tc

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.

Notes

See also

Link.friction


Robotics Toolbox for MATLAB © 1990-2014 Peter Corke.