SerialLink

Serial-link robot class

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

Methods

plot display graphical representation of robot
plot3d display 3D graphical model of robot
teach drive the graphical robot
getpos get position of graphical robot
jtraj a joint space trajectory
edit display and edit kinematic and dynamic parameters
isspherical test if robot has spherical wrist
islimit test if robot at joint limit
isconfig test robot joint configuration
fkine forward kinematics
A link transforms
trchain forward kinematics as a chain of elementary transforms
ikine6s inverse kinematics for 6-axis spherical wrist revolute robot
ikine inverse kinematics using iterative numerical method
ikunc inverse kinematics using optimisation
ikcon inverse kinematics using optimisation with joint limits
ikine_sym analytic inverse kinematics obtained symbolically
jacob0 Jacobian matrix in world frame
jacobn Jacobian matrix in tool frame
jacob_dot Jacobian derivative
maniplty manipulability
vellipse display velocity ellipsoid
fellipse display force ellipsoid
qmincon null space motion to centre joints between limits
accel joint acceleration
coriolis Coriolis joint force
dyn show dynamic properties of links
friction friction force
gravload gravity joint force
inertia joint inertia matrix
cinertia Cartesian inertia matrix
nofriction set friction parameters to zero
rne inverse dynamics
fdyn forward dynamics
payload add a payload in end-effector frame
perturb randomly perturb link dynamic parameters
gravjac gravity load and Jacobian
paycap payload capacity
pay payload effect
sym a symbolic version of the object
gencoords symbolic generalized coordinates
genforces symbolic generalized forces
issym test if object is symbolic

Properties (read/write)

links vector of Link objects (1xN)
gravity direction of gravity [gx gy gz]
base pose of robot's base (4x4 homog xform)
tool robot's tool transform, T6 to tool tip (4x4 homog xform)
qlim joint limits, [qmin qmax] (Nx2)
offset kinematic joint coordinate offsets (Nx1)
name name of robot, used for graphical display
manuf annotation, manufacturer's name
comment annotation, general comment
plotopt options for plot() method (cell array)
fast use MEX version of RNE. Can only be set true if the mex file exists. Default is true.

Properties (read only)

n number of joints
config joint configuration string, eg. 'RRRRRR'
mdh kinematic convention boolean (0=DH, 1=MDH)
theta kinematic: joint angles (1xN)
d kinematic: link offsets (1xN)
a kinematic: link lengths (1xN)
alpha kinematic: link twists (1xN)

Overloaded operators

R1*R2 concatenate two SerialLink manipulators R1 and R2

Note

Reference

See also

Link, DHFactor


SerialLink.SerialLink

Create a SerialLink robot object

R = SerialLink(links, options) is a robot object defined by a vector of Link class objects which can be instances of Link, Revolute, Prismatic, RevoluteMDH or PrismaticMDH.

R = SerialLink(options) is a null robot object with no links.

R = SerialLink([R1 R2 ...], options) concatenate robots, the base of R2 is attached to the tip of R1. Can also be written R1*R2 etc.

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

R = SerialLink(dh, options) is a robot object with kinematics defined by the matrix dh which has one row per joint and each row is [theta d a alpha] and joints are assumed revolute. An optional fifth column sigma indicate revolute (sigma=0, default) or prismatic (sigma=1).

Options

'name', NAME set robot name property to NAME
'comment', COMMENT set robot comment property to COMMENT
'manufacturer', MANUF set robot manufacturer property to MANUF
'base', T set base transformation matrix property to T
'tool', T set tool transformation matrix property to T
'gravity', G set gravity vector property to G
'plotopt', P set default options for .plot() to P
'plotopt3d', P set default options for .plot3d() to P
'nofast' don't use RNE MEX file

Examples

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

Note

See also

Link, Revolute, Prismatic, RevoluteMDH, PrismaticMDH, SerialLink.plot


SerialLink.A

Link transformation matrices

s = R.A(J, qj) is an SE(3) homogeneous transform (4x4) that transforms from link frame {J-1} to frame {J} which is a function of the J'th joint variable qj.

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.

Exmaples

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 4 5 6], q)

where q is 1x6 and the elements q(3) .. q(6) are used.

Notes


SerialLink.accel

Manipulator forward dynamics

qdd = R.accel(q, qd, torque) is a vector (Nx1) of joint accelerations that result from applying the actuator force/torque to the manipulator robot R in state q and qd, 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).

Note

References

See also

SerialLink.rne, SerialLink, ode45


SerialLink.animate

Update a robot animation

R.animate(q) updates an existing animation for the robot R. This will have been created using R.plot(). Updates graphical instances of this robot in all figures.

Notes

See also

SerialLink.plot


SerialLink.char

Convert to string

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

Cartesian inertia matrix

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.

See also

SerialLink.inertia, SerialLink.rne


SerialLink.collisions

Perform collision checking

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 and associate 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.

Trajectory operation

If q is MxN it is taken as a pose sequence and C is Mx1 and the collision value applies to the pose of the corresponding row of q. tdyn is 4x4xMxP.

Notes

Author

Bryan Moutrie

See also

collisionmodel, SerialLink


SerialLink.coriolis

Coriolis matrix

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

Notes

See also

SerialLink.rne


SerialLink.display

Display parameters

R.display() displays the robot parameters in human-readable form.

Notes

See also

SerialLink.char, SerialLink.dyn


SerialLink.dyn

Print inertial properties

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.

See also

Link.dyn


SerialLink.edit

Edit kinematic and dynamic parameters of a seriallink manipulator

R.edit displays the kinematic parameters of the robot as an editable table in a new figure.

R.edit('dyn') as above but also displays the dynamic parameters.

Notes


SerialLink.fdyn

Integrate forward dynamics

[T,q,qd] = R.fdyn(T, torqfun) integrates the dynamics of the robot over the time interval 0 to T and returns vectors of time T, joint position q and joint velocity qd. The initial joint position and velocity are zero. The torque applied to the joints is computed by the user-supplied control function torqfun:

TAU = TORQFUN(T, Q, QD)

where q and qd are the manipulator joint coordinate and velocity state respectively, and T is the current time.

[ti,q,qd] = R.fdyn(T, torqfun, q0, qd0) as above but allows the initial joint position and velocity to be specified.

[T,q,qd] = R.fdyn(T1, torqfun, q0, qd0, ARG1, ARG2, ...) allows optional arguments to be passed through to the user-supplied control function:

TAU = TORQFUN(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 = mytorqfun(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, @mytorqfun, qstar, P, D);

Note

See also

SerialLink.accel, SerialLink.nofriction, SerialLink.rne, ode45



SerialLink.fkine

Forward kinematics

T = R.fkine(q, options) is the pose of the robot end-effector as an SE(3) homogeneous transformation (4x4) 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 3d matrix (4x4xK) where the last subscript is the index along the path.

[T,all] = R.fkine(q) as above but all (4x4xN) is the pose of the link frames 1 to N, such that all(:,:,k) is the pose of link frame k.

Options

'deg' Assume that revolute joint coordinates are in degrees not radians

Note

See also

SerialLink.ikine, SerialLink.ikine6s


SerialLink.friction

Friction force

tau = R.friction(qd) is the vector of joint friction forces/torques for the robot moving with joint velocities qd.

The friction model includes:

See also

Link.friction


SerialLink.gencoords

Vector of symbolic generalized coordinates

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

Vector of symbolic generalized forces

q = R.genforces() is a vector (1xN) of symbols [Q1 Q2 ... QN].


SerialLink.getpos

Get joint coordinates from graphical display

q = R.getpos() returns the joint coordinates set by the last plot or teach operation on the graphical robot.

See also

SerialLink.plot, SerialLink.teach


SerialLink.gravjac

Fast gravity load and Jacobian

[tau,jac0] = R.gravjac(q) is the generalised joint force/torques due to gravity (1xN) and the manipulator Jacobian in the base frame (6xN) for robot pose q (1xN), where N is the number of robot joints.

[tau,jac0] = R.gravjac(q,grav) as above but gravity 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 pose. 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.

Notes

Author

Bryan Moutrie

See also

SerialLink.pay, SerialLink, SerialLink.gravload, SerialLink.jacob0


SerialLink.gravload

Gravity load on joints

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.

See also

SerialLink.rne, SerialLink.itorque, SerialLink.coriolis


SerialLink.ikcon

Numerical inverse kinematics with joint limits

q = R.ikcon(T) are the joint coordinates (1xN) corresponding to the robot end-effector pose T (4x4) which is a homogenenous transform.

[q,err] = robot.ikcon(T) as above but also returns err which is the scalar final value of the objective function.

[q,err,exitflag] = robot.ikcon(T) as above but also returns the status exitflag from fmincon.

[q,err,exitflag] = robot.ikcon(T, q0) as above but specify the initial joint coordinates q0 used for the minimisation.

[q,err,exitflag] = robot.ikcon(T, q0, options) as above but specify the options for fmincon to use.

Trajectory operation

In all cases if T is 4x4xM it is taken as a homogeneous transform sequence and R.ikcon() 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.

Notes

sumsqr( (inv(T)*robot.fkine(q) - eye(4)) * omega )

Where omega is some gain matrix, currently not modifiable.

Author

Bryan Moutrie

See also

SerialLink.ikunc, fmincon, SerialLink.ikine, SerialLink.fkine


SerialLink.ikine

Numerical inverse kinematics

q = R.ikine(T) are the joint coordinates (1xN) corresponding to the robot end-effector pose T (4x4) which is a homogenenous transform.

q = R.ikine(T, q0, options) specifies the initial estimate of the joint coordinates.

This method can be used for robots with 6 or more degrees of freedom.

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.

q = R.ikine(T, q0, m, options) similar to above but where m is a mask vector (1x6) which 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 m = [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.

Trajectory operation

In all cases if T is 4x4xM it is taken as a homogeneous transform sequence and R.ikine() 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.

Options

'pinv' use pseudo-inverse instead of Jacobian transpose (default)
'ilimit', L set the maximum iteration count (default 1000)
'tol', T set the tolerance on error norm (default 1e-6)
'alpha', A set step size gain (default 1)
'varstep' enable variable step size if pinv is false
'verbose' show number of iterations for each point
'verbose=2' show state at each iteration
'plot' plot iteration state versus time

References

Notes

See also

SerialLink.ikcon, SerialLink.ikunc, SerialLink.fkine, SerialLink.ikine6s


SerialLink.ikine3

Inverse kinematics for 3-axis robot with no wrist

q = R.ikine3(T) is the joint coordinates 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

Notes

Reference

Inverse kinematics for a PUMA 560 based on the equations by Paul and Zhang From The International Journal of Robotics Research Vol. 5, No. 2, Summer 1986, p. 32-44

Author

Robert Biro with Gary Von McMurray, GTRI/ATRP/IIMB, Georgia Institute of Technology 2/13/95

See also

SerialLink.FKINE, SerialLink.IKINE


SerialLink.ikine6s

Analytical inverse kinematics

q = R.ikine6s(T) is the joint coordinates (1xN) corresponding to the robot end-effector pose T represented by an SE(3) homogenenous transform (4x4). 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)

Notes

Reference

Author

See also

SerialLink.FKINE, SerialLink.IKINE


SerialLink.ikine_sym

Symbolic inverse kinematics

q = R.IKINE_SYM(k, options) is a cell array (Cx1) of inverse kinematic solutions of the SerialLink object ROBOT. The cells of q represent the different possible configurations. Each cell of q is a vector (Nx1), and element J is the symbolic expressions for the J'th joint angle. The solution is in terms of the desired end-point pose of the robot which is represented by the symbolic matrix (3x4) with elements

nx ox ax tx
ny oy ay ty
nz oz az tz

where the first three columns specify orientation and the last column specifies translation.

k <= N can have only specific values:

Options

'file', F Write the solution to an m-file named F

Example

mdl_planar2
sol = p2.ikine_sym(2);
length(sol)
ans =
2       % there are 2 solutions
s1 = sol{1}  % is one solution
q1 = s1(1);      % the expression for q1
q2 = s1(2);      % the expression for q2

Notes


SerialLink.ikinem

Numerical inverse kinematics by minimization

q = R.ikinem(T) is the joint coordinates corresponding to the robot end-effector pose T which is a homogenenous transform.

q = R.ikinem(T, q0, options) specifies the initial estimate of the joint coordinates.

In all cases if T is 4x4xM it is taken as a homogeneous transform sequence and R.ikinem() 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.

Options

'pweight', P weighting on position error norm compared to rotation error (default 1)
'stiffness', S Stiffness used to impose a smoothness contraint on joint angles, useful when N is large (default 0)
'qlimits' Enforce joint limits
'ilimit', L Iteration limit (default 1000)
'nolm' Disable Levenberg-Marquadt

Notes

See also

fminsearch, fmincon, SerialLink.fkine, SerialLink.ikine, tr2angvec


SerialLink.ikunc

Numerical inverse manipulator without joint limits

q = R.ikunc(T) are the joint coordinates (1xN) corresponding to the robot end-effector pose T (4x4) which is a homogenenous transform, and N is the number of robot joints.

[q,err] = robot.ikunc(T) as above but also returns err which is the scalar final value of the objective function.

[q,err,exitflag] = robot.ikunc(T) as above but also returns the status exitflag from fminunc.

[q,err,exitflag] = robot.ikunc(T, q0) as above but specify the initial joint coordinates q0 used for the minimisation.

[q,err,exitflag] = robot.ikunc(T, q0, options) as above but specify the options for fminunc to use.

Trajectory operation

In all cases if T is 4x4xM it is taken as a homogeneous transform sequence and R.ikunc() 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.

Notes

sumsqr( (inv(T)*robot.fkine(q) - eye(4)) * omega )

Where omega is some gain matrix, currently not modifiable.

Author

Bryan Moutrie

See also

SerialLink.ikcon, fmincon, SerialLink.ikine, SerialLink.fkine


SerialLink.inertia

Manipulator inertia matrix

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

See also

SerialLink.RNE, SerialLink.CINERTIA, SerialLink.ITORQUE


SerialLink.isconfig

Test for particular joint configuration

R.isconfig(s) is true if the robot has the joint configuration string given by the string s.

Example:

robot.isconfig('RRRRRR');

See also

SerialLink.config


SerialLink.islimit

Joint limit test

v = R.islimit(q) is a vector of boolean values, one per joint, false (0) if q(i) is within the joint limits, else true (1).

Notes

See also

Link.islimit


SerialLink.isspherical

Test for spherical wrist

R.isspherical() is true if the robot has a spherical wrist, that is, the last 3 axes are revolute and their axes intersect at a point.

See also

SerialLink.ikine6s


SerialLink.issym

Check if SerialLink object is a symbolic model

res = R.issym() is true if the SerialLink manipulator R has symbolic parameters

Authors

Joern Malzahn, (joern.malzahn@tu-dortmund.de)


SerialLink.itorque

Inertia torque

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.

Note

See also

SerialLink.inertia, SerialLink.rne


SerialLink.jacob0

Jacobian in world coordinates

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 roll-pitch-yaw angles
'eul' Compute analytical Jacobian with rotation rates in terms of Euler angles
'trans' Return translational submatrix of Jacobian
'rot' Return rotational submatrix of Jacobian

Note

See also

SerialLink.jacobn, jsingu, deltatr, tr2delta, jsingu


SerialLink.jacob_dot

Derivative of Jacobian

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

References

See also

SerialLink.jacob0, diff2tr, tr2diff


SerialLink.jacobn

Jacobian in end-effector frame

jn = R.jacobn(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 = jn*QD in the end-effector frame.

Options

'trans' Return translational submatrix of Jacobian
'rot' Return rotational submatrix of Jacobian

Notes

References

See also

SerialLink.jacob0, jsingu, delta2tr, tr2delta


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 with default zero boundary conditions for velocity and acceleration. The trajectory q has one row per time step, and one column per joint, where N is the number of robot joints.

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().

Additional options are passed as trailing arguments to the inverse kinematic function.

See also

jtraj, SerialLink.ikine, SerialLink.ikine6s


SerialLink.maniplty

Manipulability measure

m = R.maniplty(q, options) is the manipulability index (scalar) for the robot at the joint configuration q (1xN) where N is the number of robot joints. It indicates dexterity, that is, how isotropic the robot's motion is with respect to the 6 degrees of Cartesian motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity.

If q is a matrix (MxN) then m (Mx1) is a vector of manipulability indices for each joint configuration specified by a row of q.

[m,ci] = R.maniplty(q, options) as above, but for the case of the Asada measure returns the Cartesian inertia matrix ci.

Two measures can be computed:

Options

'T' manipulability for transational motion only (default)
'R' manipulability for rotational motion only
'all' manipulability for all motions
'dof', D D is a vector (1x6) with non-zero elements if the corresponding DOF is to be included for manipulability
'yoshikawa' use Yoshikawa algorithm (default)
'asada' use Asada algorithm

Notes

References

See also

SerialLink.inertia, SerialLink.jacob0


SerialLink.mtimes

Concatenate robots

R = R1 * R2 is a robot object that is equivalent to mechanically attaching robot R2 to the end of robot R1.

Notes


SerialLink.nofriction

Remove friction

rnf = R.nofriction() is a robot object with the same parameters as R but with non-linear (Coulomb) friction coefficients set to zero.

rnf = R.nofriction('all') as above but viscous and Coulomb friction coefficients set to zero.

rnf = R.nofriction('viscous') as above but viscous friction coefficients are set to zero.

Notes

See also

SerialLink.fdyn, Link.nofriction


SerialLink.pay

Joint forces due to payload

tau = R.PAY(w, J) returns the generalised joint force/torques due to a payload wrench w (1x6) and where the manipulator Jacobian is J (6xN), and N is the number of robot joints.

tau = R.PAY(q, w, f) as above but the Jacobian is calculated at pose q (1xN) in the frame given by f which is '0' for world frame, 'n' for end-effector frame.

Uses the formula tau = J'w, where w is a wrench vector applied at the end effector, w = [Fx Fy Fz Mx My Mz]'.

Trajectory operation

In the case q is MxN or J is 6xNxM then tau is MxN where each row is the generalised force/torque at the pose given by corresponding row of q.

Notes

Author

Bryan Moutrie

See also

SerialLink.paycap, SerialLink.jacob0, SerialLink.jacobn


SerialLink.paycap

Static payload capacity of a robot

[wmax,J] = R.paycap(q, w, f, tlim) returns the maximum permissible payload wrench wmax (1x6) applied at the end-effector, and the index of the joint J which hits its force/torque limit at that wrench. q (1xN) is the manipulator pose, w the payload wrench (1x6), f the wrench reference frame (either '0' or 'n') and tlim (2xN) is a matrix of joint forces/torques (first row is maximum, second row minimum).

Trajectory operation

In the case q is MxN then wmax is Mx6 and J is Mx1 where the rows are the results at the pose given by corresponding row of q.

Notes

Author

Bryan Moutrie

See also

SerialLink.pay, SerialLink.gravjac, SerialLink.gravload


SerialLink.payload

Add payload mass

R.payload(m, p) adds a payload with point mass m at position p in the end-effector coordinate frame.

Notes

See also

SerialLink.rne, SerialLink.gravload


SerialLink.perturb

Perturb robot parameters

rp = R.perturb(p) is a new robot object in which the dynamic parameters (link mass and inertia) have been perturbed. The perturbation is multiplicative so that values are multiplied by random numbers in the interval (1-p) to (1+p). The name string of the perturbed robot is prefixed by 'p/'.

Useful for investigating the robustness of various model-based control schemes. For example to vary parameters in the range +/- 10 percent is:

r2 = p560.perturb(0.1);

SerialLink.plot

Graphical display and animation

R.plot(q, options) displays a graphical animation of a robot based on the kinematic model. A stick figure polyline joins the origins of the link coordinate frames. The robot is displayed at the joint angle q (1xN), or if a matrix (MxN) it is animated as the robot moves along the M-point trajectory.

Options

'workspace', W Size of robot 3D workspace, W = [xmn, xmx ymn ymx zmn zmx]
'floorlevel', L Z-coordinate of floor (default -1)
'delay', D Delay betwen frames for animation (s)
'fps', fps Number of frames per second for display, inverse of 'delay' option
'[no]loop' Loop over the trajectory forever
'[no]raise' Autoraise the figure
'movie', M Save frames as files in the folder M
'trail', L Draw a line recording the tip path, with line style L
'scale', S Annotation scale factor
'zoom', Z Reduce size of auto-computed workspace by Z, makes robot look bigger
'ortho' Orthographic view
'perspective' Perspective view (default)
'view', V Specify view V='x', 'y', 'top' or [az el] for side elevations, plan view, or general view by azimuth and elevation angle.
'top' View from the top.
'[no]shading' Enable Gouraud shading (default true)
'lightpos', L Position of the light source (default [0 0 20])
'[no]name' Display the robot's name
'[no]wrist' Enable display of wrist coordinate frame
'xyz' Wrist axis label is XYZ
'noa' Wrist axis label is NOA
'[no]arrow' Display wrist frame with 3D arrows
'[no]tiles' Enable tiled floor (default true)
'tilesize', S Side length of square tiles on the floor (default 0.2)
'tile1color', C Color of even tiles [r g b] (default [0.5 1 0.5] light green)
'tile2color', C Color of odd tiles [r g b] (default [1 1 1] white)
'[no]shadow' Enable display of shadow (default true)
'shadowcolor', C Colorspec of shadow, [r g b]
'shadowwidth', W Width of shadow line (default 6)
'[no]jaxes' Enable display of joint axes (default false)
'[no]jvec' Enable display of joint axis vectors (default false)
'[no]joints' Enable display of joints
'jointcolor', C Colorspec for joint cylinders (default [0.7 0 0])
'jointdiam', D Diameter of joint cylinder in scale units (default 5)
'linkcolor', C Colorspec of links (default 'b')
'[no]base' Enable display of base 'pedestal'
'basecolor', C Color of base (default 'k')
'basewidth', W Width of base (default 3)

The options come from 3 sources and are processed in order:

Many boolean options can be enabled or disabled with the 'no' prefix. The various option sources can toggle an option, the last value is taken.

Graphical annotations and options

The robot is displayed as a basic stick figure robot with annotations such as:

which are controlled by options.

The size of the annotations is determined using a simple heuristic from the workspace dimensions. This dimension can be changed by setting the multiplicative scale factor using the 'mag' option.

Figure behaviour

Multiple views of the same robot

If one or more plots of this robot already exist then these will all be moved according to the argument q. All robots in all windows with the same name will be moved.

Create a robot in figure 1

figure(1)
p560.plot(qz);

Create a robot in figure 2

figure(2)
p560.plot(qz);

Now move both robots

p560.plot(qn)

Multiple robots in the same figure

Multiple robots can be displayed in the same plot, by using "hold on" before calls to robot.plot().

Create a robot in figure 1

figure(1)
p560.plot(qz);

Make a clone of the robot named bob

bob = SerialLink(p560, 'name', 'bob');

Draw bob in this figure

hold on
bob.plot(qn)

To animate both robots so they move together:

qtg = jtraj(qr, qz, 100);
for q=qtg'
p560.plot(q');
bob.plot(q');
end

Making an animation movie

ffmpeg -r 10 -i %04d.png out.avi

Notes

See also

SerialLink.plot3d, plotbotopt, SerialLink.animate, SerialLink.teach, SerialLink.fkine


SerialLink.plot3d

Graphical display and animation of solid model robot

R.plot3d(q, options) displays and animates a solid model of the robot. The robot is displayed at the joint angle q (1xN), or if a matrix (MxN) it is animated as the robot moves along the M-point trajectory.

Options

'color', C A cell array of color names, one per link. These are mapped to RGB using colorname(). If not given, colors come from the axis ColorOrder property.
'alpha', A Set alpha for all links, 0 is transparant, 1 is opaque (default 1)
'path', P Overide path to folder containing STL model files
'workspace', W Size of robot 3D workspace, W = [xmn, xmx ymn ymx zmn zmx]
'floorlevel', L Z-coordinate of floor (default -1)
'delay', D Delay betwen frames for animation (s)
'fps', fps Number of frames per second for display, inverse of 'delay' option
'[no]loop' Loop over the trajectory forever
'[no]raise' Autoraise the figure
'movie', M Save frames as files in the folder M
'scale', S Annotation scale factor
'ortho' Orthographic view (default)
'perspective' Perspective view
'view', V Specify view V='x', 'y', 'top' or [az el] for side elevations, plan view, or general view by azimuth and elevation angle.
'[no]wrist' Enable display of wrist coordinate frame
'xyz' Wrist axis label is XYZ
'noa' Wrist axis label is NOA
'[no]arrow' Display wrist frame with 3D arrows
'[no]tiles' Enable tiled floor (default true)
'tilesize', S Side length of square tiles on the floor (default 0.2)
'tile1color', C Color of even tiles [r g b] (default [0.5 1 0.5] light green)
'tile2color', C Color of odd tiles [r g b] (default [1 1 1] white)
'[no]jaxes' Enable display of joint axes (default true)
'[no]joints' Enable display of joints
'[no]base' Enable display of base shape

Notes

Authors

See also

SerialLink.plot, plotbotopt3d, SerialLink.animate, SerialLink.teach, SerialLink.fkine


SerialLink.qmincon

Use redundancy to avoid joint limits

qs = R.qmincon(q) exploits null space motion and returns a set of joint angles qs (1xN) that result in the same end-effector pose but are away from the joint coordinate limits. N is the number of robot joints.

[q,err] = R.qmincon(q) as above but also returns err which is the scalar final value of the objective function.

[q,err,exitflag] = R.qmincon(q) as above but also returns the status exitflag from fmincon.

Trajectory operation

In all cases if q is MxN it is taken as a pose sequence and R.qmincon() returns the adjusted joint coordinates (MxN) corresponding to each of the poses in the sequence.

err and exitflag are also Mx1 and indicate the results of optimisation for the corresponding trajectory step.

Notes

Author

Bryan Moutrie

See also

SerialLink.ikcon, SerialLink.ikunc, SerialLink.jacob0


SerialLink.rne

Inverse dynamics

tau = R.rne(q, qd, qdd) is the joint torque required for the robot R to achieve the specified joint position q (1xN), velocity qd (1xN) and acceleration qdd (1xN), where N is the number of robot joints.

tau = R.rne(q, qd, qdd, grav) as above but overriding the gravitational acceleration vector (3x1) in the robot object R.

tau = R.rne(q, qd, qdd, grav, fext) as above but specifying a wrench acting on the end of the manipulator which is a 6-vector [Fx Fy Fz Mx My Mz].

tau = R.rne(x) as above where x=[q,qd,qdd] (1x3N).

tau = R.rne(x, grav) as above but overriding the gravitational acceleration vector in the robot object R.

tau = R.rne(x, grav, fext) as above but specifying a wrench acting on the end of the manipulator which is a 6-vector [Fx Fy Fz Mx My Mz].

[tau,wbase] = R.rne(x, grav, fext) as above but the extra output is the wrench on the base.

Trajectory operation

If q,qd and qdd (MxN), or x (Mx3N) are matrices with M rows representing a trajectory then tau (MxN) is a matrix with rows corresponding to each trajectory step.

MEX file operation

This algorithm is relatively slow, and a MEX file can provide better performance. The MEX file is executed if:

Notes

See also

SerialLink.accel, SerialLink.gravload, SerialLink.inertia




SerialLink.teach

Graphical teach pendant

R.teach(q, options) allows the user to "drive" a graphical robot by means of a graphical slider panel. If no graphical robot exists one is created in a new window. Otherwise all current instances of the graphical robot are driven. The robots are set to the initial joint angles q.

R.teach(options) as above but with options and the initial joint angles are taken from the pose of an existing graphical robot, or if that doesn't exist then zero.

Options

'eul' Display tool orientation in Euler angles (default)
'rpy' Display tool orientation in roll/pitch/yaw angles
'approach' Display tool orientation as approach vector (z-axis)
'[no]deg' Display angles in degrees (default true)
'callback', CB Set a callback function, called with robot object and joint angle vector: CB(R, Q)

Example

To display the velocity ellipsoid for a Puma 560

p560.teach('callback', @(r,q) r.vellipse(q));

GUI

Notes

See also

SerialLink.plot, SerialLink.getpos


SerialLink.trchain

Convert to elementary transform sequence

s = R.TRCHAIN(options) is a sequence of elementary transforms that describe the kinematics of the serial link robot arm. The string s comprises a number of tokens of the form X(ARG) where X is one of Tx, Ty, Tz, Rx, Ry, or Rz. ARG is a joint variable, or a constant angle or length dimension.

For example:

>> mdl_puma560
>> p560.trchain
ans =
Rz(q1)Rx(90)Rz(q2)Tx(0.431800)Rz(q3)Tz(0.150050)Tx(0.020300)Rx(-90)
Rz(q4)Tz(0.431800)Rx(90)Rz(q5)Rx(-90)Rz(q6)

Options

'[no]deg' Express angles in degrees rather than radians (default deg)
'sym' Replace length parameters by symbolic values L1, L2 etc.

See also

trchain, trotx, troty, trotz, transl



Robotics Toolbox for MATLAB © 1990-2014 Peter Corke.