<< Link Link RP >>

Robotics_Toolbox >> Robotics_Toolbox > Link > Link

Link

Robot manipulator Link class

Introduction

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

Properties (read/write)

theta kinematic joint angle
dkinematiclink offset
akinematiclink length
alphakinematiclink twist
sigmakinematic0 if revolute, 1 if prismatic
mdhkinematic0 if standard D&H, else 1
offsetkinematicjoint variable offset
qlimkinematicjoint variable limits [min max]
mdynamiclink mass
rdynamiclink COG wrt link coordinate frame 3x1
Idynamiclink inertia matrix, symmetric 3x3, about link COG
Bdynamiclink viscous friction (motor referred)
Tcdynamiclink Coulomb friction
Gactuatorgear ratio
Jmactuatormotor inertia (motor referred)

Calling Sequence

L = Link() 
L = Link(L1) 
L = Link(OPTIONS)

Old syntax:
L = Link(DH,OPTIONS)
DH = [THETA D A ALPHA]

Alternative syntax:
L = Link(THETA, D, A, ALPHA, SIGMA, OFFSET, DH_TYPE)

Description

L = Link() is a Link object with default parameters.

L = Link(L1) is a Link object that is a deep copy of the link object L1.

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

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

Notes

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, 0, 'standard');
//the flag 'standard' is not strictly necessary but adds clarity.

//For a modified Denavit-Hartenberg link
L3 = Link( 0, 0.15005, 0.0203, -%pi/2, 0, 'modified');

Old Sintax

L = Link(DH, OPTIONS)

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

- DH = [THETA D A ALPHA SIGMA OFFSET] where OFFSET is a constant displacement between the user joint angle vector and the true kinematic solution.

- DH = [THETA D A ALPHA SIGMA] where SIGMA=0 for a revolute and 1 for a prismatic joint, OFFSET is zero.

- DH = [THETA D A ALPHA], joint is assumed revolute and OFFSET is zero.

Options

'standard' :

for standard D&H parameters, can be abbreviated to 'std' (default)

'modified' :

for modified D&H parameters, can be abbreviated to 'mod'

'revolute' :

for a revolute joint, can be abbreviated to 'r' (default)

'prismatic' :

for a prismatic joint, can be abbreviated to 'p'

Alternative Sintax

L = Link(THETA, D, A, ALPHA)
L = Link(THETA, D, A, ALPHA, DH_TYPE)
L = Link(THETA, D, A, ALPHA, SIGMA, DH_TYPE)
L = Link(THETA, D, A, ALPHA, SIGMA, OFFSET, DH_TYPE)

L = Link(THETA, D, A, ALPHA, SIGMA, OFFSET, DH_TYPE) is a link object using the specified kinematic convention and with the parameters of the old syntax.

OFFSET is a constant displacement between the user joint angle vector and the true kinematic solution.

SIGMA=0 for a revolute and SIGMA=1 for a prismatic joint.

DH_TYPE is the type of Denavit-Hartenberg convencion used. It can take two values:

- "standard" or "std" for standard D&H parameters (default).

- "modified" or "mod" for modified D&H parameters.

SIGMA, OFFSET, DH_TYPE can be omitted; will be considered the default values: joint is assumed revolute, with no offset and using the standard Denavit-Hartenberg convencion.

Bibliography

Robotics, Vision & Control, Chap 7, P. Corke, Springer 2011.

See also

Authors


Report an issue
<< Link Link RP >>