<< SerialLink SerialLink accel >>

Robotics_Toolbox >> Robotics_Toolbox > SerialLink > SerialLink

SerialLink

SerialLink robot object

Description

A concrete class that represents a serial-link arm-type robot. The mechanism is described using Denavit-Hartenberg parameters, one set per joint.

Properties (read/write)

linksvector of Link objects (1xN)
gravitydirection of gravity [gx gy gz]
basepose of robot's base (4x4 homog xform)
tooldrobot's tool transform, T6 to tool tip (4x4 homog xform)
qlimjoint limits, [qmin qmax] (Nx2)
offsetkinematic joint coordinate offsets (Nx1)
namename of robot, used for graphical display
manufannotation, manufacturer's name
commentannotation, general comment
plotoptoptions for "plot_robot()" function.

Object properties (read only)

nnumber of joints
configjoint configuration string, eg. 'RRRRRR'
mdhkinematic convention boolean (0=DH, 1=MDH)

Emulated methods

All methods invoke external functions by passing the robot as the first variable. The methods that require onlt the robot object as input parameter can be called as methods in object-oriented programming. If you need to specify more than one input parameter, the call as a "method" of robot "class" is no longer valid. In this case you must use the syntax "function(robot, parameters)" instead of "robot.function()".

Ie. "robot.isspherical()" works while "robot.jacob0(q, options)" generates an error. The correct syntax is "jacob0(robot, q, options).

plot_robot - display graphical representation of robot

teach - drive the graphical robot

isspherical - test if robot has spherical wrist

islimit - test if robot at joint limit

fkine - forward kinematics

ikine6s - inverse kinematics for 6-axis spherical wrist revolute robot

ikine3 - inverse kinematics for 3-axis revolute robot

ikine - inverse kinematics using iterative method

jacob0 - Jacobian matrix in world frame

jacobn - Jacobian matrix in tool frame

maniplty - manipulability

jtraj - a joint space trajectory

accel - joint acceleration

coriolis - Coriolis joint force

dyn - show dynamic properties of links

fdyn - joint motion

friction - friction force

gravload - gravity joint force

inertia - joint inertia matrix

nofriction set friction parameters to zero

rne - joint torque/force

payload - add a payload in end-effector frame

perturb - randomly perturb link dynamic parameters

Calling Sequence

R = SerialLink(LINKS,OPTIONS)
R = SerialLink(R1,OPTIONS)   
R = SerialLink(list(R1,R2,...), OPTIONS)

Description

R = SerialLink(LINKS, OPTIONS) is a robot object defined by a list of Link objects. LINKS is a list of Link, ie. "LINKS = list(L1,L2);"

R = SerialLink(list(R1,R2,...), OPTIONS) concatenate robots, the base of R2 is attached to the tip of R1.

R = SerialLink(R1, options) is a deep copy of the robot object R1, with all the same properties.

Parameters

'name', name :

set robot name property

'comment', comment :

set robot comment property

'manufacturer', manuf :

set robot manufacturer property

'base', base :

set base transformation matrix property

'tool', tool :

set tool transformation matrix property

'gravity', g :

set gravity vector property

'plotopt', po :

set plotting options property

Examples

// Create a 2-link robot
L = list();
L(1) = Link([ 0     0   1  0], 'standard');
L(2) = Link([ 0     0   1  0], 'standard');
twolink = SerialLink(L, 'name', 'two link');

// Create a copy of the robot twolink
R1 = SerialLink(twolink)

// Load a model of robot, see help mdl_puma560
mdl_puma560

// Robot objects can be concatenated in two ways
R = R1 * mdl_puma560;
R = SerialLink(list(R1,mdl_puma560));

Notes

Bibliography

[1] Robotics, Vision & Control, Chaps 7-9, P. Corke, Springer 2011.

[2] Robot, Modeling & Control, M.Spong, S. Hutchinson & M. Vidyasagar, Wiley 2006.

See also

Authors


Report an issue
<< SerialLink SerialLink accel >>