Serial-link robot class
A concrete class that represents a serial-link arm-type robot. Each link and joint in the chain is described by a Link-class object using Denavit-Hartenberg parameters (standard or modified).
name | robot name |
manuf | robot manufacturer |
comment | robot comment |
links | list containing the robot Link objects |
gravity | gravity vector |
base | base transformation matrix |
tool | tool transformation matrix |
offset | joint variable offsets |
handles | currently unused |
lineopt | currently unused |
shadowopt | currently unused |
plotopt | currently unused |
qlim | link limits (currently unused) |
q | joint variables (currently unused) |
n | number of robot joints |
mdh | 0 if standard D&H convention is used, otherwise 1 for modified D&H |
config | String specifying the robot configuration: R indicates revolute joints, P indicates prismatic joints |
R = SerialLink() R = SerialLink(list(L1,L2..), OPTIONS) R = SerialLink(R1, OPTIONS) R = SerialLink(list(R1,R2..), OPTIONS)
R = SerialLink() is a robot object with default parameters.
R = SerialLink(list(L1,L2..), OPTIONS) is a robot object that is a concatenation of link objects L1, L2,... .
R = SerialLink(R1, OPTIONS) is a robot object that is a deep copy of the robot object R1.
R = SerialLink(list(R1,R2..), OPTIONS) is a robot object that is a concatenation of robot objects R1, R2,... .
set the robot name (string)
set the manufacturer name (string)
set a comment (string)
set a (3x1) gravity vector
set the base-to-link-0 homogeneous transformation matrix (4x4)
set the link-n-to-tool homogeneous transformation matrix (4x4)
set the links offset vector (1xn)
set the joint limits matrix (nx2)
set the joints vector (1xn) (currently unused)
// A serial link manipulator comprises a series of links. Each link is described // by four Denavit-Hartenberg parameters. // // Let's define a simple 2 link manipulator. The first link is L1 = Link('d', 0, 'a', 1, 'alpha', %pi/2) L2 = Link('d', 0, 'a', 1, 'alpha', 0) // join these two links into a serial-link manipulator L = list(L1,L2) Robot = SerialLink(L, 'name', 'my robot') // change the default gravity vector so as to work into the outer space Robot = SerialLink(L, 'gravity', [0; 0; 0]) // make a copy of the robot Robot1 = SerialLink(Robot) // or alternatively Robot1 = Robot // concatenate two robots R = list(Robot, Robot1) Robot2 = SerialLink(R) // or alternatively Robot2 = Robot * Robot1 | ![]() | ![]() |
Link elements passed in must be all standard, or all modified, DH parameters.
When robots are concatenated the intermediate base and tool transforms are removed since general constant transforms cannot be represented in Denavit-Hartenberg notation. In the same way, the gravity vector is set to its default ([0; 0; 9.81])