Arm Type Robots - DH¶
Code author: Jesse Haviland
SerialLink¶
@author Jesse Haviland
-
class
ropy.robot.SerialLink.
SerialLink
(L, name='noname', manufacturer='', base=SE3(array([[1.0, 0.0, 0.0, 0.0], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]])), tool=SE3(array([[1.0, 0.0, 0.0, 0.0], [0.0, 1.0, 0.0, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]])), gravity=array([0.0, 0.0, 9.81]))[source]¶ Bases:
object
A superclass for arm type robots. 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).
- Parameters
L (list(n)) – Series of links which define the robot
name (string) – Name of the robot
manufacturer (string) – Manufacturer of the robot
base (SE3) – Locaation of the base
tool (SE3) – Location of the tool
gravity – The gravity vector
- Notes
Link subclass elements passed in must be all standard, or all modified, DH parameters.
- References
Robotics, Vision & Control, Chaps 7-9, P. Corke, Springer 2011.
Robot, Modeling & Control, M.Spong, S. Hutchinson & M. Vidyasagar, Wiley 2006.
-
property
links
¶
-
property
n
¶
-
property
mdh
¶
-
property
d
¶
-
property
a
¶
-
property
theta
¶
-
property
r
¶
-
property
offset
¶
-
property
qlim
¶
-
property
manuf
¶
-
property
control_type
¶
-
property
gravity
¶
-
property
name
¶
-
property
base
¶
-
property
tool
¶
-
property
q
¶
-
property
qd
¶
-
property
qdd
¶
-
A
(joints, q=None)[source]¶ Link forward kinematics.
T = A(joints, q) transforms between link frames for the J’th joint. q is a vector (n) of joint variables. For: - standard DH parameters, this is from frame {J-1} to frame {J}. - modified DH parameters, this is from frame {J} to frame {J+1}.
T = A(joints) as above except uses the stored q value of the robot object.
- Parameters
joints (int, tuple or 2 element list) – Joints to transform to (int) or between (list/tuple)
q (float ndarray(1,n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values)
- Return T
The transform between link 0 and joints or joints[0] and joints[1]
- Rtype T
SE3
- Notes
Base and tool transforms are not applied.
-
islimit
(q=None)[source]¶ Joint limit test.
v = islimit(q) returns a list of boolean values indicating if the joint configuration q is in vialation of the joint limits.
v = jointlimit() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values)
- Return v
is a vector of boolean values, one per joint, False if q[i] is within the joint limits, else True
- Rtype v
bool list
-
isspherical
()[source]¶ Test for spherical wrist. Tests if the robot has a spherical wrist, that is, the last 3 axes are revolute and their axes intersect at a point.
- Returns
True if spherical wrist
- Return type
bool
-
payload
(m, p=array([0.0, 0.0, 0.0]))[source]¶ payload(m, p) adds payload mass adds a payload with point mass m at position p in the end-effector coordinate frame.
payload(m) adds payload mass adds a payload with point mass m at in the end-effector coordinate frame.
payload(0) removes added payload.
- Parameters
m (float) – mass (kg)
p (float ndarray(3,1)) – position in end-effector frame
-
jointdynamics
(q, qd)[source]¶ Transfer function of joint actuator.
tf = jointdynamics(qd, q) calculates a vector of n continuous-time transfer function objects that represent the transfer function 1/(Js+B) for each joint based on the dynamic parameters of the robot and the configuration q (n). n is the number of robot joints.
tf = jointdynamics(qd) as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values)
qd (float ndarray(n)) – The joint velocities of the robot
-
isprismatic
()[source]¶ Identify prismatic joints.
p = isprismatic() returns a bool list identifying the prismatic joints within the robot
- Returns
a list of bool variables, one per joint, true if the corresponding joint is prismatic, otherwise false.
- Return type
bool list
-
isrevolute
()[source]¶ Identify revolute joints.
p = isrevolute() returns a bool list identifying the revolute joints within the robot
- Returns
a list of bool variables, one per joint, true if the corresponding joint is revolute, otherwise false.
- Return type
bool list
-
todegrees
(q=None)[source]¶ Convert joint angles to degrees.
qdeg = toradians(q) converts joint coordinates q to degrees.
qdeg = toradians() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values)
- Returns
a vector of joint coordinates where those elements corresponding to revolute joints are converted from radians to degrees. Elements corresponding to prismatic joints are copied unchanged.
- Return type
float ndarray(n)
-
toradians
(q)[source]¶ Convert joint angles to radians.
qrad = toradians(q) converts joint coordinates q to radians.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Not optional, stored q is always radians)
- Returns
a vector of joint coordinates where those elements corresponding to revolute joints are converted from degrees to radians. Elements corresponding to prismatic joints are copied unchanged.
- Return type
float ndarray(n)
-
twists
(q=None)[source]¶ Joint axis twists.
tw, T = twists(q) calculates a vector of Twist objects (n) that represent the axes of the joints for the robot with joint coordinates q (n). Also returns T0 which is an SE3 object representing the pose of the tool.
tw, T = twists() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values)
- Return tw
a vector of Twist objects
- Rtype tw
float ndarray(n,)
- Return T0
Represents the pose of the tool
- Rtype T0
SE3
-
fkine
(q=None)[source]¶ T = fkine(q) evaluates forward kinematics for the robot at joint configuration q.
T = fkine() as above except uses the stored q value of the robot object.
Trajectory operation: for each point on a trajectory of joints q
- Parameters
q (float ndarray(n) or (nxm)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values). If q is a matrix the rows are interpreted as the generalized joint coordinates for a sequence of points along a trajectory. q(j,i) is the j’th joint parameter for the i’th trajectory point.
- Return T
Homogeneous transformation matrix or trajectory
- Rtype T
SE3 or SE3 list
- Notes
The robot’s base or tool transform, if present, are incorporated into the result.
Joint offsets, if defined, are added to q before the forward kinematics are computed.
-
allfkine
(q=None)[source]¶ Tall = allfkine(q) evaluates fkine for each joint within a robot and returns a trajecotry of poses.
Tall = allfkine() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return T
Homogeneous transformation trajectory
- Rtype T
SE3 list
- Notes
The robot’s base or tool transform, if present, are incorporated into the result.
Joint offsets, if defined, are added to q before the forward kinematics are computed.
-
jacobe
(q=None)[source]¶ Je = jacobe(q) is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity. v = Je*qd in the end-effector frame.
Je = jacobe() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return J
The manipulator Jacobian in ee frame
- Return type
float ndarray(6,n)
-
jacob0
(q=None)[source]¶ J0 = jacob0(q) is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity. v = J0*qd in the base frame.
J0 = jacob0() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return J
The manipulator Jacobian in ee frame
- Return type
float ndarray(6,n)
-
jacob0v
(q=None)[source]¶ Jv = jacob0v(q) is the spatial velocity Jacobian, at joint configuration q, which relates the velocity in the end-effector frame to velocity in the base frame
Jv = jacob0v() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Returns J
The velocity Jacobian in 0 frame
- Rtype J
float ndarray(6,6)
-
jacobev
(q=None)[source]¶ Jv = jacobev(q) is the spatial velocity Jacobian, at joint configuration q, which relates the velocity in the base frame to the velocity in the end-effector frame.
Jv = jacobev() as above except uses the stored q value of the robot object.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Returns J
The velocity Jacobian in ee frame
- Rtype J
float ndarray(6,6)
-
accel
(qd, torque, q=None)[source]¶ qdd = accel(qd, torque, q) calculates a vector (n) of joint accelerations that result from applying the actuator force/torque (n) to the manipulator in state q (n) and qd (n), and n is the number of robot joints.
a = accel(qd, torque) as above except uses the stored q value of the robot object.
If q, qd, torque are matrices (nxk) then qdd is a matrix (nxk) where each row is the acceleration corresponding to the equivalent cols of q, qd, torque.
- Parameters
qd (float ndarray(n)) – The joint velocities of the robot
torque (float ndarray(n)) – The joint torques of the robot
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return qdd
The joint accelerations of the robot
- Rtype qdd
float ndarray(n)
- Notes
Useful for simulation of manipulator dynamics, in conjunction with a numerical integration function.
Uses the method 1 of Walker and Orin to compute the forward dynamics.
Featherstone’s method is more efficient for robots with large numbers of joints.
Joint friction is considered.
- References
Efficient dynamic computer simulation of robotic mechanisms, M. W. Walker and D. E. Orin, ASME Journa of Dynamic Systems, Measurement and Control, vol. 104, no. 3, pp. 205-211, 1982.
-
nofriction
(coulomb=True, viscous=False)[source]¶ NFrobot = nofriction(coulomb, viscous) copies the robot and returns a robot with the same parameters except, the Coulomb and/or viscous friction parameter set to zero
NFrobot = nofriction(coulomb, viscous) copies the robot and returns a robot with the same parameters except the Coulomb friction parameter is set to zero
- Parameters
coulomb (bool) – if True, will set the coulomb friction to 0
- Returns
A copy of the robot with dynamic parameters perturbed
- Return type
-
pay
(W, q=None, J=None, frame=1)[source]¶ tau = pay(W, J) Returns the generalised joint force/torques due to a payload wrench W applied to the end-effector. Where the manipulator Jacobian is J (6xn), and n is the number of robot joints.
tau = pay(W, q, frame) as above but the Jacobian is calculated at pose q in the frame given by frame which is 0 for base frame, 1 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 nxm or J is 6xnxm then tau is nxm where each row is the generalised force/torque at the pose given by corresponding row of q.
- Parameters
W (float ndarray(6)) – A wrench vector applied at the end effector, W = [Fx Fy Fz Mx My Mz]
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
J (float ndarray(6,n)) – The manipulator Jacobian (Optional, if not supplied will use the q value).
frame (int) – The frame in which to torques are expressed in when J is not supplied. 0 means base frame of the robot, 1 means end- effector frame
- Return tau
The joint forces/torques due to w
- Rtype tau
float ndarray(n)
- Notes
Wrench vector and Jacobian must be from the same reference frame.
Tool transforms are taken into consideration when frame=1.
Must have a constant wrench - no trajectory support for this yet.
-
friction
(qd)[source]¶ tau = friction(qd) calculates the vector of joint friction forces/torques for the robot moving with joint velocities qd.
The friction model includes:
Viscous friction which is a linear function of velocity.
Coulomb friction which is proportional to sign(qd).
- Parameters
qd (float ndarray(n)) – The joint velocities of the robot
- Returns
The joint friction forces.torques for the robot
- Return type
float ndarray(n,)
- Notes
The friction value should be added to the motor output torque, it has a negative value when qd>0.
The returned friction value is referred to the output of the gearbox.
The friction parameters in the Link object are referred to the motor.
Motor viscous friction is scaled up by G^2.
Motor Coulomb friction is scaled up by G.
The appropriate Coulomb friction value to use in the non-symmetric case depends on the sign of the joint velocity, not the motor velocity.
The absolute value of the gear ratio is used. Negative gear ratios are tricky: the Puma560 has negative gear ratio for joints 1 and 3.
-
cinertia
(q=None)[source]¶ M = cinertia(q) is the nxn Cartesian (operational space) inertia matrix which relates Cartesian force/torque to Cartesian acceleration at the joint configuration q.
M = cinertia() as above except uses the stored q value of the robot object.
If q is a matrix (nxk), each row is interpretted as a joint state vector, and the result is a 3d-matrix (nxnxk) where each plane corresponds to the cinertia for the corresponding row of q.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return M
The inertia matrix
- Rtype M
float ndarray(n,n)
-
inertia
(q=None)[source]¶ SerialLink.INERTIA Manipulator inertia matrix
I = inertia(q) is the symmetric joint inertia matrix (nxn) which relates joint torque to joint acceleration for the robot at joint configuration q.
I = inertia() as above except uses the stored q value of the robot object.
If q is a matrix (nxk), 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.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return I
The inertia matrix
- Rtype I
float ndarray(n,n)
- Notes
The diagonal elements I(J,J) are the inertia seen by joint actuator J.
The off-diagonal elements I(J,K) are coupling inertias that relate acceleration on joint J to force/torque on joint K.
The diagonal terms include the motor inertia reflected through the gear ratio.
-
coriolis
(qd, q=None)[source]¶ C = coriolis(qd, q) calculates 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.
C = coriolis(qd) as above except uses the stored q value of the robot object.
If q and qd are matrices (nxk), 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.
- Parameters
qd (float ndarray(n)) – The joint velocities of the robot
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return C
The Coriolis/centripetal matrix
- Rtype C
float ndarray(n,n)
- Notes
Joint viscous friction is also a joint force proportional to velocity but it is eliminated in the computation of this value.
Computationally slow, involves n^2/2 invocations of RNE.
-
itorque
(qdd, q=None)[source]¶ Inertia torque
tauI = itorque(qdd, q) is the inertia force/torque vector (n) at the specified joint configuration q (n) and acceleration qdd (n), and n is the number of robot joints. taui = inertia(q) * qdd.
If q and qdd are matrices (nxk), each row is interpretted as a joint state vector, and the result is a matrix (nxk) where each row is the corresponding joint torques.
- Parameters
qdd (float ndarray(n)) – The joint accelerations of the robot
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Return taui
The inertia torque vector
- Rtype tai
float ndarray(n)
- Notes
If the robot model contains non-zero motor inertia then this will included in the result.
-
gravjac
(q=None, grav=None)[source]¶ tauB = gravjac(q, grav) calculates the generalised joint force/torques due to gravity.
tauB = gravjac() as above except uses the stored q and gravitational acceleration of the robot object.
Trajectory operation: If q is nxm where n is the number of robot joints then a trajectory is assumed where each row of q corresponds to a robot configuration. tau (nxm) is the generalised joint torque, each row corresponding to an input pose, and jacob0 (6xnxm) where each plane is a Jacobian corresponding to an input pose.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
grav (float ndarray(3,)) – The gravity vector (Optional, if not supplied will use the stored gravity values).
- Return tau
The generalised joint force/torques due to gravity
- Rtype tau
float ndarray(n,)
- Notes
The gravity vector is defined by the SerialLink property if not explicitly given.
Does not use inverse dynamics function RNE.
Faster than computing gravity and Jacobian separately.
-
gravload
(q=None, grav=None)[source]¶ taug = gravload(q, grav) calculates the joint gravity loading (n) for the robot in the joint configuration q, and the gravitational load grav.
taug = gravload() as above except uses the stored q and gravitational acceleration of the robot object.
If q is a matrix (nxm) each column is interpreted as a joint configuration vector, and the result is a matrix (nxm) each column being the corresponding joint torques.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
grav (float ndarray(3)) – The gravity vector (Optional, if not supplied will use the stored gravity values).
- Return taug
The generalised joint force/torques due to gravity
- Rtype taug
float ndarray(n)
-
ikcon
(T, q0=None)[source]¶ Inverse kinematics by optimization with joint limits
q, success, err = ikcon(T, q0) calculates the joint coordinates (1xn) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and N is the number of robot joints. Initial joint coordinates Q0 used for the minimisation.
q, success, err = ikcon(T) as above but q0 is set to 0.
Trajectory operation: In all cases if T is a vector of SE3 objects or a homogeneous transform sequence (4x4xm) then returns the joint coordinates corresponding to each of the transforms in the sequence. q is nxm 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. Retruns trajectory of joints q (nxm), list of success (m) and list of errors (m)
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
q0 (float ndarray(n) (default all zeros)) – initial joint configuration (default all zeros)
- Retrun q
The calculated joint values
- Rtype q
float ndarray(n)
- Retrun success
IK solved (True) or failed (False)
- Rtype success
bool
- Retrun error
Final pose error
- Rtype error
float
- Notes
Joint limits are considered in this solution.
Can be used for robots with arbitrary degrees of freedom.
In the case of multiple feasible solutions, the solution returned depends on the initial choice of q0.
Works by minimizing the error between the forward kinematics of the joint angle solution and the end-effector frame as an optimisation.
The objective function (error) is described as: sumsqr( (inv(T)*robot.fkine(q) - eye(4)) * omega ) Where omega is some gain matrix, currently not modifiable.
-
ikine
(T, ilimit=500, rlimit=100, tol=1e-10, Y=0.1, Ymin=0, mask=None, q0=None, search=False, slimit=100, transpose=None)[source]¶ Inverse kinematics by optimization without joint limits
q, success, err = ikine(T) are the joint coordinates corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and n is the number of robot joints.
This method can be used for robots with any number of degrees of freedom.
Trajectory operation: In all cases if T is a vector of SE3 objects (m) or a homogeneous transform sequence (4x4xm) then returns the joint coordinates corresponding to each of the transforms in the sequence. q is nxm 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. Retruns trajectory of joints q (nxm), list of success (m) and list of errors (m)
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
ilimit (int (default 500)) – maximum number of iterations
rlimit (int (default 100)) – maximum number of consecutive step rejections
tol (float (default 1e-10)) – final error tolerance
Y (float (default 0.1)) – initial value of lambda
Ymin (float (default 0)) – minimum allowable value of lambda
mask (float ndarray(6)) – mask vector that correspond to translation in X, Y and Z and rotation about X, Y and Z respectively.
q0 (float ndarray(n) (default all zeros)) – initial joint configuration (default all zeros)
search (bool) – search over all configurations
slimit (int (default 100)) – maximum number of search attempts
transpose (float) – use Jacobian transpose with step size A, rather than Levenberg-Marquadt
- Retrun q
The calculated joint values
- Rtype q
float ndarray(n)
- Retrun success
IK solved (True) or failed (False)
- Rtype success
bool
- Retrun error
If failed, what went wrong
- Rtype error
List of String
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.
In this case we specify the ‘mask’ option where the mask vector (1x6) 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 use the option: mask = [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.
- Notes
Solution is computed iteratively.
Implements a Levenberg-Marquadt variable step size solver.
The tolerance is computed on the norm of the error between current and desired tool pose. This norm is computed from distances and angles without any kind of weighting.
The inverse kinematic solution is generally not unique, and depends on the initial guess q0 (defaults to 0).
The default value of q0 is zero which is a poor choice for most manipulators (eg. puma560, twolink) since it corresponds to a kinematic singularity.
Such a solution is completely general, though much less efficient than specific inverse kinematic solutions derived symbolically, like ikine6s or ikine3.
This approach allows a solution to be obtained at a singularity, but the joint angles within the null space are arbitrarily assigned.
Joint offsets, if defined, are added to the inverse kinematics to generate q.
Joint limits are not considered in this solution.
The ‘search’ option peforms a brute-force search with initial conditions chosen from the entire configuration space.
If the search option is used any prismatic joint must have joint limits defined.
- References
Robotics, Vision & Control, P. Corke, Springer 2011, Section 8.4.
-
ikine3
(T, left=True, elbow_up=True)[source]¶ Analytical inverse kinematics for three link robots
q = ikine3(T) is the joint coordinates (3) 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). This will have the arm to the left and the elbow up.
q = ikine3(T, left, elbow_up) as above except the arm location and elbow position can be specified.
Trajectory operation: In all cases if T is a vector of SE3 objects (m) or a homogeneous transform sequence (4x4xm) then returns the joint coordinates corresponding to each of the transforms in the sequence. Q is 3xm.
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
left (bool) – True for arm to the left (default), else arm to the right
elbow_up (bool) – True for elbow up (default), else elbow down
- Retrun q
The calculated joint values
- Rtype q
float ndarray(n)
- Notes
The same as IKINE6S without the wrist.
The inverse kinematic solution is generally not unique, and depends on the configuration string.
Joint offsets, if defined, are added to the inverse kinematics to generate q.
- 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
-
ikine6s
(T, left=True, elbow_up=True, wrist_flip=False)[source]¶ Analytical inverse kinematics
q, err = ikine6s(T) are the joint coordinates (n) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and n is the number of robot joints. This is an analytic solution for a 6-axis robot with a spherical wrist (the most common form for industrial robot arms).
q, err = ikine6s(T, left, elbow_up, wrist_flip) as above except the arm location, elbow position, and wrist orientation can be specified.
Trajectory operation: In all cases if T is a vector of SE3 objects (1xM) or a homogeneous transform sequence (4x4xM) then the inverse kinematics is computed for all m poses resulting in q (nxm) with each row representing the joint angles at the corresponding pose.
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
left (bool) – True for arm to the left (default), else arm to the right
elbow_up (bool) – True for elbow up (default), else elbow down
wrist_flip (bool) – False for wrist not flipped (default), else wrist flipped (rotated by 180 deg)
- Return q
The calculated joint values
- Rtype q
float ndarray(n)
- Return err
Any errors encountered
- Rtype err
list String
- Notes
- Treats a number of specific cases:
Robot with no shoulder offset
Robot with a shoulder offset (has lefty/righty configuration)
Robot with a shoulder offset and a prismatic third joint (like Stanford arm)
The Puma 560 arms with shoulder and elbow offsets (4 lengths parameters)
The Kuka KR5 with many offsets (7 length parameters)
The inverse kinematics for the various cases determined using ikine_sym.
The inverse kinematic solution is generally not unique, and depends on the configuration string.
Joint offsets, if defined, are added to the inverse kinematics to generate q.
Only applicable for standard Denavit-Hartenberg parameters
- Reference
Inverse kinematics for a PUMA 560, Paul and Zhang, The International Journal of Robotics Research, Vol. 5, No. 2, Summer 1986, p. 32-44
-
ikinem
(T, q0=None, pweight=1.0, stiffness=0.0, qlimits=True, ilimit=1000, nolm=False)[source]¶ Numerical inverse kinematics with joint limits q, success, err = ikinem(T) is the joint coordinates corresponding to the robot end-effector pose T which is a homogenenous transform.
q, success, err = R.ikinem(T, q0, pweight, stiffness, qlimits, ilimit, nolm) as above except with options defined such as the initial estimate of the joint coordinates q0.
Trajectory operation: In all cases if T is 4x4xm it is taken as a homogeneous transform sequence and ikinem(T) returns the joint coordinates corresponding to each of the transforms in the sequence. q is nxm 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.
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
pweight (float) – weighting on position error norm compared to rotation error (default 1)
stiffness (float) – Stiffness used to impose a smoothness contraint on joint angles, useful when n is large (default 0)
qlimits (bool) – Enforce joint limits (default True)
ilimit (bool) – Iteration limit (default 1000)
nolm (bool) – Disable Levenberg-Marquadt
- Retrun q
The calculated joint values
- Rtype q
float ndarray(n)
- Retrun success
IK solved (True) or failed (False)
- Rtype success
bool
- Retrun error
Final pose error
- Rtype error
float
- Notes
PROTOTYPE CODE UNDER DEVELOPMENT, intended to do numerical inverse kinematics with joint limits
The inverse kinematic solution is generally not unique, and depends on the initial guess q0 (defaults to 0).
The function to be minimized is highly nonlinear and the solution is often trapped in a local minimum, adjust q0 if this happens.
The default value of q0 is zero which is a poor choice for most manipulators (eg. puma560, twolink) since it corresponds to a kinematic singularity.
Such a solution is completely general, though much less efficient than specific inverse kinematic solutions derived symbolically, like ikine6s or ikine3.
Uses Levenberg-Marquadt minimizer LMFsolve if it can be found, if ‘nolm’ is not given, and ‘qlimits’ false
The error function to be minimized is computed on the norm of the error between current and desired tool pose. This norm is computed from distances and angles and ‘pweight’ can be used to scale the position error norm to be congruent with rotation error norm.
This approach allows a solution to obtained at a singularity, but the joint angles within the null space are arbitrarily assigned.
Joint offsets, if defined, are added to the inverse kinematics to generate q.
Joint limits become explicit contraints if ‘qlimits’ is set.
-
ikunc
(T, q0=None, ilimit=1000)[source]¶ Inverse manipulator by optimization without joint limits
q, success, err = ikunc(T) are the joint coordinates (n) corresponding to the robot end-effector pose T which is an SE3 object or homogenenous transform matrix (4x4), and n is the number of robot joints. Also returns success and err which is the scalar final value of the objective function.
q, success, err = robot.ikunc(T, q0, ilimit) as above but specify the initial joint coordinates q0 used for the minimisation.
Trajectory operation: In all cases if T is a vector of SE3 objects (m) or a homogeneous transform sequence (4x4xm) then returns the joint coordinates corresponding to each of the transforms in the sequence. q is nxm 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.
- Parameters
T (SE3 or SE3 trajectory) – The desired end-effector pose
ilimit (bool) – Iteration limit (default 1000)
- Retrun q
The calculated joint values
- Rtype q
float ndarray(n)
- Retrun success
IK solved (True) or failed (False)
- Rtype success
bool
- Retrun error
Final pose error
- Rtype error
float
- Notes
Joint limits are not considered in this solution.
Can be used for robots with arbitrary degrees of freedom.
In the case of multiple feasible solutions, the solution returned depends on the initial choice of q0
Works by minimizing the error between the forward kinematics of the joint angle solution and the end-effector frame as an optimisation.
The objective function (error) is described as: sumsqr( (inv(T)*robot.fkine(q) - eye(4)) * omega ) Where omega is some gain matrix, currently not modifiable.
-
rne
(qdd, qd, q=None, grav=None, fext=None)[source]¶ Inverse dynamics
tau = rne(qdd, qd, q, grav, fext) is the joint torque required for the robot to achieve the specified joint position q (1xn), velocity qd (1xn) and acceleration qdd (1xn), where n is the number of robot joints. fext describes the wrench acting on the end-effector
Trajectory operation: If q, qd and qdd (nxm) are matrices with m cols representing a trajectory then tau (nxm) is a matrix with cols corresponding to each trajectory step.
- Parameters
qdd (float ndarray(n)) – The joint accelerations of the robot
qd (float ndarray(n)) – The joint velocities of the robot
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
grav (float ndarray(6)) – Gravity vector to overwrite robots gravity value
fext (float ndarray(6)) – Specify wrench acting on the end-effector W=[Fx Fy Fz Mx My Mz]
- Notes
The torque computed contains a contribution due to armature inertia and joint friction.
If a model has no dynamic parameters set the result is zero.
-
delete_rne
()[source]¶ Frees the memory holding the robot object in c if the robot object has been initialised in c.
-
paycap
(w, tauR, frame=1, q=None)[source]¶ Static payload capacity of a robot
wmax, joint = paycap(q, w, f, tauR) returns the maximum permissible payload wrench wmax (6) applied at the end-effector, and the index of the joint (zero indexed) which hits its force/torque limit at that wrench. q (n) is the manipulator pose, w the payload wrench (6), f the wrench reference frame and tauR (nx2) is a matrix of joint forces/torques (first col is maximum, second col minimum).
Trajectory operation: In the case q is nxm then wmax is Mx6 and J is Mx1 where the rows are the results at the pose given by corresponding row of q.
- Parameters
w (float ndarray(n)) – The payload wrench
tauR (float ndarray(n,2)) – Joint torque matrix minimum and maximums
frame (int) – The frame in which to torques are expressed in when J is not supplied. 0 means base frame of the robot, 1 means end- effector frame
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Retrun wmax
The maximum permissible payload wrench
- Rtype wmax
float ndarray(6)
- Retrun joint
The joint index (zero indexed) which hits its force/torque limit
- Rtype joint
int
- Notes
Wrench vector and Jacobian must be from the same reference frame
Tool transforms are taken into consideration for frame=1.
-
jacob_dot
(q=None, qd=None)[source]¶ Jqd = jacob_dot(q, qd) is the product (6) of the derivative of the manipulator Jacobian (in the world frame) and the joint rates.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
qd (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored qd values).
- Retrun Jdot
The derivative of the manipulator Jacobian
- Rtype Jdot
float ndarray(n)
- Notes
This term appears in the formulation for operational space control xdd = J(q)qdd + Jdot(q)qd
Written as per the reference and not very efficient.
- References
Fundamentals of Robotics Mechanical Systems (2nd ed) J. Angleles, Springer 2003.
A unified approach for motion and force control of robot manipulators: The operational space formulation O Khatib, IEEE Journal on Robotics and Automation, 1987.
-
maniplty
(q=None, method='yoshikawa', axes=[1, 1, 1, 1, 1, 1])[source]¶ Manipulability measure
m = maniplty(q) is the yoshikawa manipulability index (scalar) for the robot at the joint configuration q (n) 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. Yoshikawa’s manipulability measure is based on the shape of the velocity ellipsoid and depends only on kinematic parameters.
m = maniplty(q, method=’asada’) as above except computes the asada manipulability measure. Asada’s manipulability measure is based on the shape of the acceleration ellipsoid which in turn is a function of the Cartesian inertia matrix and the dynamic parameters. The scalar measure computed here is the ratio of the smallest/largest ellipsoid axis. Ideally the ellipsoid would be spherical, giving a ratio of 1, but in practice will be less than 1.
m = maniplty(q, method, axes) as above except axes specity which of the 6 degrees-of-freedom to concider in the measurement. For example set axes=[1, 1, 1, 0, 0, 0] to consider only translation or axes=[0, 0, 0, 1, 1, 1] to consider only rotation. Defaults to all motion.
If q is a matrix (nxm) then m (mx1) is a vector of manipulability indices for each joint configuration specified by a row of q.
[m, CI] = maniplty(q, OPTIONS) as above, but for the case of the Asada measure returns the Cartesian inertia matrix CI.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
method (string) – Which method to use, ‘yoshikawa’ (default) or ‘asada’
axes (int list) – The degrees-of-freedom to be included for manipulability
- Notes
The ‘all’ option includes rotational and translational dexterity, but this involves adding different units. It can be more useful to look at the translational and rotational manipulability separately.
Examples in the RVC book (1st edition) can be replicated by using the ‘all’ option
- References
Analysis and control of robot manipulators with redundancy, T. Yoshikawa, Robotics Research: The First International Symposium (M. Brady and R. Paul, eds.), pp. 735-747, The MIT press, 1984.
A geometrical representation of manipulator dynamics and its application to arm design, H. Asada, Journal of Dynamic Systems, Measurement, and Control, vol. 105, p. 131, 1983.
Robotics, Vision & Control, P. Corke, Springer 2011.
-
perterb
(p=0.1)[source]¶ Perturb robot parameters
rp = 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 = puma.perturb(0.1)
- Parameters
p (float) – The percent (+/-) to be perturbed. Default 10%
- Returns
A copy of the robot with dynamic parameters perturbed
- Return type
-
qmincon
(q=None)[source]¶ qs, success, err = qmincon(q) exploits null space motion and returns a set of joint angles qs (n) that result in the same end-effector pose but are away from the joint coordinate limits. n is the number of robot joints. Success retruns True for successful optimisation. err which is the scalar final value of the objective function.
Trajectory operation: In all cases if q is nxm it is taken as a pose sequence and qmincon() returns the adjusted joint coordinates (nxm) corresponding to each of the poses in the sequence.
err and success are also m and indicate the results of optimisation for the corresponding trajectory step.
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
- Retrun qs
The calculated joint values
- Rtype qs
float ndarray(n)
- Retrun success
Optimisation solved (True) or failed (False)
- Rtype success
bool
- Retrun err
Final value of the objective function
- Rtype err
float
- Notes
Robot must be redundant.
-
teach
(block=True, q=None, limits=None, jointaxes=True, eeframe=True, shadow=True, name=True)[source]¶ Graphical teach pendant
env = teach() creates a matplotlib plot which allows the user to “drive” a graphical robot using a graphical slider panel. The robot’s inital joint configuration is robot.q. This will block the programs execution. The plot will autoscale with an aspect ratio of 1.
env = teach(q) as above except the robot’s initial configuration is set to q.
env = teach(block=False) as avove except the plot is non-blocking. Note that the plot will exit when the python script finishes executing.
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
jointaxes (bool) – (Plot Option) Plot an arrow indicating the axes in which the joint revolves around(revolute joint) or translates along (prosmatic joint)
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
shadow (bool) – (Plot Option) Plot a shadow of the robot in the x-y plane
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
- Notes
The slider limits are derived from the joint limit properties. If not set then
For revolute joints they are assumed to be [-pi, +pi]
For prismatic joint they are assumed unknown and an error occurs.
-
plot
(block=True, q=None, dt=50, limits=None, vellipse=False, fellipse=False, jointaxes=True, eeframe=True, shadow=True, name=True)[source]¶ Graphical display and animation
env = plot() displays a graphical view of a robot based on the kinematic model, at it’s stored q value. A stick figure polyline joins the origins of the link coordinate frames. This method will be blocking. The plot will autoscale with an aspect ratio of 1.
env = plot(q) as above except the robot is plotted with joint angles q
env = plot(block=False) as avove except the plot in non-blocking. Note that the plot will exit when the python script finishes executing.
env = plot(q, dt) as above except q is an nxm trajectory of joint angles. This creates an animation of the robot moving through the trajectories with a gap dt milliseconds in between.
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
dt (int) – if q is a trajectory, this describes the delay in milliseconds between frames
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
vellipse (bool) – (Plot Option) Plot the velocity ellipse at the end-effector
vellipse – (Plot Option) Plot the force ellipse at the end-effector
jointaxes (bool) – (Plot Option) Plot an arrow indicating the axes in which the joint revolves around(revolute joint) or translates along (prosmatic joint)
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
shadow (bool) – (Plot Option) Plot a shadow of the robot in the x-y plane
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
-
vellipse
(q=None, opt='trans', centre=[0, 0, 0])[source]¶ Create a velocity ellipsoid object for plotting
env = vellipse() creates a velocity ellipsoid for the robot at pose robot.q. The ellipsoid is centered at the origin.
env = vellipse(q) as above except the robot is plotted with joint angles q
env = vellipse(opt) as above except opt is ‘trans’ or ‘rot’ will plot either the translational or rotational velocity ellipsoid.
env = vellipse(centre) as above except centre is either a 3 vector or ‘ee’ which is the centre location of the ellipsoid
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
opt (string) – ‘trans’ or ‘rot’ will plot either the translational or rotational velocity ellipsoid
centre (list or str('ee')) –
- Retrun
An EllipsePlot object
- Return type
EllipsePlot
-
fellipse
(q=None, opt='trans', centre=[0, 0, 0])[source]¶ Create a force ellipsoid object for plotting
env = fellipse() creates a force ellipsoid for the robot at pose robot.q. The ellipsoid is centered at the origin.
env = fellipse(q) as above except the robot is plotted with joint angles q
env = fellipse(opt) as above except opt is ‘trans’ or ‘rot’ will plot either the translational or rotational force ellipsoid.
env = fellipse(centre) as above except centre is either a 3 vector or ‘ee’ which is the centre location of the ellipsoid
- Parameters
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
opt (string) – ‘trans’ or ‘rot’ will plot either the translational or rotational force ellipsoid
centre (list or str('ee')) –
- Retrun
An EllipsePlot object
- Return type
EllipsePlot
-
plot_vellipse
(block=True, q=None, vellipse=None, limits=None, opt='trans', centre=[0, 0, 0], jointaxes=True, eeframe=True, shadow=True, name=True)[source]¶ Plot the velocity ellipsoid for seriallink manipulator
env = plot_vellipse() displays the velocity ellipsoid for the robot at pose robot.q. The ellipsoid is centered at the origin. This method will be blocking. The plot will autoscale with an aspect ratio of 1.
env = plot_vellipse(block=False) as avove except the plot in non-blocking. Note that the plot will exit when the python script finishes executing.
env = plot_vellipse(q) as above except the robot is plotted with joint angles q
env = plot_vellipse(vellipse) specifies a custon ellipse to plot. If not supplied this function calculates the vellipse based on q
env = plot_vellipse(limits) as above except the view limits of the plot are set by limits.
env = plot_vellipse(opt) as above except opt is ‘trans’ or ‘rot’ will plot either the translational or rotational velocity ellipsoid.
env = plot_vellipse(centre) as above except centre is either a 3 vector or ‘ee’ which is the centre location of the ellipsoid
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
vellipse (EllipsePlot) – the vellocity ellipsoid to plot
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
opt (string) – ‘trans’ or ‘rot’ will plot either the translational or rotational velocity ellipsoid
centre (list or str('ee')) – The coordinates to plot the vellipse [x, y, z] or ‘ee’ to plot at the end-effector location
jointaxes (bool) – (Plot Option) Plot an arrow indicating the axes in which the joint revolves around(revolute joint) or translates along (prosmatic joint)
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
shadow (bool) – (Plot Option) Plot a shadow of the robot in the x-y plane
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
-
plot_fellipse
(block=True, q=None, fellipse=None, limits=None, opt='trans', centre=[0, 0, 0], jointaxes=True, eeframe=True, shadow=True, name=True)[source]¶ Plot the force ellipsoid for seriallink manipulator
env = plot_fellipse() displays the force ellipsoid for the robot at pose robot.q. The ellipsoid is centered at the origin. This method will be blocking. The plot will autoscale with an aspect ratio of 1.
env = plot_fellipse(block=False) as avove except the plot in non-blocking. Note that the plot will exit when the python script finishes executing.
env = plot_fellipse(q) as above except the robot is plotted with joint angles q
env = plot_fellipse(fellipse) specifies a custon ellipse to plot. If not supplied this function calculates the fellipse based on q
env = plot_fellipse(limits) as above except the view limits of the plot are set by limits.
env = plot_fellipse(opt) as above except opt is ‘trans’ or ‘rot’ will plot either the translational or rotational force ellipsoid.
env = plot_fellipse(centre) as above except centre is either a 3 vector or ‘ee’ which is the centre location of the ellipsoid
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
fellipse (EllipsePlot) – the vellocity ellipsoid to plot
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
opt (string) – ‘trans’ or ‘rot’ will plot either the translational or rotational force ellipsoid
centre (list or str('ee')) – The coordinates to plot the fellipse [x, y, z] or ‘ee’ to plot at the end-effector location
jointaxes (bool) – (Plot Option) Plot an arrow indicating the axes in which the joint revolves around(revolute joint) or translates along (prosmatic joint)
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
shadow (bool) – (Plot Option) Plot a shadow of the robot in the x-y plane
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
-
plot2
(block=True, q=None, dt=50, limits=None, vellipse=False, fellipse=False, eeframe=True, name=False)[source]¶ 2D Graphical display and animation
env = plot2() displays a 2D graphical view of a robot based on the kinematic model, at it’s stored q value. A stick figure polyline joins the origins of the link coordinate frames. This method will be blocking. The plot will autoscale with an aspect ratio of 1.
env = plot2(q) as above except the robot is plotted with joint angles q
env = plot2(block=False) as avove except the plot in non-blocking. Note that the plot will exit when the python script finishes executing.
env = plot2(q, dt) as above except q is an nxm trajectory of joint angles. This creates an animation of the robot moving through the trajectories with a gap dt milliseconds in between.
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
dt (int) – if q is a trajectory, this describes the delay in milliseconds between frames
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
vellipse (bool) – (Plot Option) Plot the velocity ellipse at the end-effector
vellipse – (Plot Option) Plot the force ellipse at the end-effector
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
-
teach2
(block=True, q=None, limits=None, eeframe=True, name=False)[source]¶ 2D Graphical teach pendant
env = teach2() creates a 2D matplotlib plot which allows the user to “drive” a graphical robot using a graphical slider panel. The robot’s inital joint configuration is robot.q. This will block the programs execution. The plot will autoscale with an aspect ratio of 1.
env = teach2(q) as above except the robot’s initial configuration is set to q.
env = teach2(block=False) as avove except the plot is non-blocking. Note that the plot will exit when the python script finishes executing.
- Parameters
block (bool) – Block operation of the code and keep the figure open
q (float ndarray(n)) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).
limits (ndarray(6)) – Custom view limits for the plot. If not supplied will autoscale, [x1, x2, y1, y2, z1, z2]
eeframe (bool) – (Plot Option) Plot the end-effector coordinate frame at the location of the end-effector. Uses three arrows, red, green and blue to indicate the x, y, and z-axes.
name (bool) – (Plot Option) Plot the name of the robot near its base
- Retrun
A reference to the PyPlot object which controls the matplotlib figure
- Return type
PyPlot
- Notes
The slider limits are derived from the joint limit properties. If not set then
For revolute joints they are assumed to be [-pi, +pi]
For prismatic joint they are assumed unknown and an error occurs.
Revolute¶
@author: Jesse Haviland
-
class
ropy.robot.Revolute.
Revolute
(d=0.0, alpha=0.0, a=0.0, mdh=0.0, offset=0.0, qlim=array([0.0, 0.0]), flip=False, m=0.0, r=array([0.0, 0.0, 0.0]), I=array([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]]), Jm=0.0, B=0.0, Tc=array([0.0, 0.0]), G=1.0)[source]¶ Bases:
ropy.robot.Link.Link
A class for revolute link types
- Parameters
d (float) – kinematic - link offset
alpha (float) – kinematic - link twist
a (float) – kinematic - link length
sigma (int) – kinematic - 0 if revolute, 1 if prismatic
mdh (int) – kinematic - 0 if standard D&H, else 1
offset (float) – kinematic - joint variable offset
qlim (float ndarray(1,2)) – joint variable limits [min max]
flip (bool) – joint moves in opposite direction
m (float) – dynamic - link mass
r (float ndarray(3)) – dynamic - position of COM with respect to link frame
I (float ndarray(3,3)) – dynamic - inertia of link with respect to COM
Jm (float) – dynamic - motor inertia
B (float) – dynamic - motor viscous friction (1x1 or 2x1)
Tc (float ndarray(2)) – dynamic - motor Coulomb friction (1x2 or 2x1)
G (float) – dynamic - gear ratio
- References
Robotics, Vision & Control, P. Corke, Springer 2011, Chap 7.
-
A
(q)¶ Link transform matrix
T = 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)
- Parameters
q (float) – Joint angle (radians)
- Return T
link homogeneous transformation matrix
- Rtype T
float numpy.ndarray((4, 4))
- Notes
For a revolute joint the THETA parameter of the link is ignored, and q used instead.
For a prismatic joint the D parameter of the link is ignored, and q used instead.
The link offset parameter is added to Q before computation of the transformation matrix.
-
property
B
¶
-
property
G
¶
-
property
I
¶
-
property
Jm
¶
-
property
Tc
¶
-
property
a
¶
-
property
alpha
¶
-
property
d
¶
-
dyn
()¶ Show inertial properties of link
s = dyn() returns a string representation 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.
- Return s
The string representation of the link dynamics
- Rtype s
string
-
property
flip
¶
-
friction
(qd)¶ tau = friction(qd) Calculates the joint friction force/torque (n) for joint velocity qd (n). The friction model includes:
Viscous friction which is a linear function of velocity.
Coulomb friction which is proportional to sign(qd).
- Parameters
qd (float) – The joint velocity
- Return tau
the friction force/torque
- Rtype tau
float
- Notes
The friction value should be added to the motor output torque, it has a negative value when qd > 0.
The returned friction value is referred to the output of the gearbox.
The friction parameters in the Link object are referred to the motor.
Motor viscous friction is scaled up by G^2.
Motor Coulomb friction is scaled up by G.
The appropriate Coulomb friction value to use in the non-symmetric case depends on the sign of the joint velocity, not the motor velocity.
The absolute value of the gear ratio is used. Negative gear ratios are tricky: the Puma560 has negative gear ratio for joints 1 and 3.
-
islimit
(q)¶ Checks if the joint is exceeding a joint limit
- Returns
True if joint is exceeded
- Return type
bool
-
isprismatic
()¶ Checks if the joint is of prismatic type
- Returns
Ture if is prismatic
- Return type
bool
-
isrevolute
()¶ Checks if the joint is of revolute type
- Returns
Ture if is revolute
- Return type
bool
-
property
m
¶
-
property
mdh
¶
-
nofriction
(coulomb=True, viscous=False)¶ l2 = nofriction(coulomb, viscous) copies the link and returns a link with the same parameters except, the Coulomb and/or viscous friction parameter to zero.
l2 = nofriction() as above except the the Coulomb parameter is set to zero.
- Parameters
coulomb (bool) – if True, will set the coulomb friction to 0
viscous (bool) – if True, will set the viscous friction to 0
-
property
offset
¶
-
property
qlim
¶
-
property
r
¶
-
property
sigma
¶
-
property
theta
¶
Prismatic¶
@author: Jesse Haviland
-
class
ropy.robot.Prismatic.
Prismatic
(alpha=0.0, theta=0.0, a=0.0, mdh=0.0, offset=0.0, qlim=array([0.0, 0.0]), flip=False, m=0.0, r=array([0.0, 0.0, 0.0]), I=array([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]]), Jm=0.0, B=0.0, Tc=array([0.0, 0.0]), G=1.0)[source]¶ Bases:
ropy.robot.Link.Link
A class for prismatic link types
A subclass of the Link class for a prismatic joint: holds all information related to a robot link such as kinematics parameters, rigid-body inertial parameters, motor and transmission parameters.
- Parameters
theta (float) – kinematic: joint angle
d (float) – kinematic - link offset
alpha (float) – kinematic - link twist
a (float) – kinematic - link length
sigma (int) – kinematic - 0 if revolute, 1 if prismatic
mdh (int) – kinematic - 0 if standard D&H, else 1
offset (float) – kinematic - joint variable offset
qlim (float ndarray(1,2)) – joint variable limits [min max]
flip (bool) – joint moves in opposite direction
m (float) – dynamic - link mass
r (float ndarray(3)) – dynamic - position of COM with respect to link frame
I (float ndarray(3,3)) – dynamic - inertia of link with respect to COM
Jm (float) – dynamic - motor inertia
B (float) – dynamic - motor viscous friction (1x1 or 2x1)
Tc (float ndarray(2)) – dynamic - motor Coulomb friction (1x2 or 2x1)
G (float) – dynamic - gear ratio
- References
Robotics, Vision & Control, P. Corke, Springer 2011, Chap 7.
-
A
(q)¶ Link transform matrix
T = 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)
- Parameters
q (float) – Joint angle (radians)
- Return T
link homogeneous transformation matrix
- Rtype T
float numpy.ndarray((4, 4))
- Notes
For a revolute joint the THETA parameter of the link is ignored, and q used instead.
For a prismatic joint the D parameter of the link is ignored, and q used instead.
The link offset parameter is added to Q before computation of the transformation matrix.
-
property
B
¶
-
property
G
¶
-
property
I
¶
-
property
Jm
¶
-
property
Tc
¶
-
property
a
¶
-
property
alpha
¶
-
property
d
¶
-
dyn
()¶ Show inertial properties of link
s = dyn() returns a string representation 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.
- Return s
The string representation of the link dynamics
- Rtype s
string
-
property
flip
¶
-
friction
(qd)¶ tau = friction(qd) Calculates the joint friction force/torque (n) for joint velocity qd (n). The friction model includes:
Viscous friction which is a linear function of velocity.
Coulomb friction which is proportional to sign(qd).
- Parameters
qd (float) – The joint velocity
- Return tau
the friction force/torque
- Rtype tau
float
- Notes
The friction value should be added to the motor output torque, it has a negative value when qd > 0.
The returned friction value is referred to the output of the gearbox.
The friction parameters in the Link object are referred to the motor.
Motor viscous friction is scaled up by G^2.
Motor Coulomb friction is scaled up by G.
The appropriate Coulomb friction value to use in the non-symmetric case depends on the sign of the joint velocity, not the motor velocity.
The absolute value of the gear ratio is used. Negative gear ratios are tricky: the Puma560 has negative gear ratio for joints 1 and 3.
-
islimit
(q)¶ Checks if the joint is exceeding a joint limit
- Returns
True if joint is exceeded
- Return type
bool
-
isprismatic
()¶ Checks if the joint is of prismatic type
- Returns
Ture if is prismatic
- Return type
bool
-
isrevolute
()¶ Checks if the joint is of revolute type
- Returns
Ture if is revolute
- Return type
bool
-
property
m
¶
-
property
mdh
¶
-
nofriction
(coulomb=True, viscous=False)¶ l2 = nofriction(coulomb, viscous) copies the link and returns a link with the same parameters except, the Coulomb and/or viscous friction parameter to zero.
l2 = nofriction() as above except the the Coulomb parameter is set to zero.
- Parameters
coulomb (bool) – if True, will set the coulomb friction to 0
viscous (bool) – if True, will set the viscous friction to 0
-
property
offset
¶
-
property
qlim
¶
-
property
r
¶
-
property
sigma
¶
-
property
theta
¶
Link¶
@author: Jesse Haviland
-
class
ropy.robot.Link.
Link
(d=0.0, alpha=0.0, theta=0.0, a=0.0, sigma=0, mdh=0, offset=0.0, qlim=array([0.0, 0.0]), flip=False, m=0.0, r=array([0.0, 0.0, 0.0]), I=array([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]]), Jm=0.0, B=0.0, Tc=array([0.0, 0.0]), G=1.0)[source]¶ Bases:
object
A link superclass for all link types. A Link object holds all information related to a robot joint and link such as kinematics parameters, rigid-body inertial parameters, motor and transmission parameters.
- Parameters
theta (float) – kinematic: joint angle
d (float) – kinematic - link offset
alpha (float) – kinematic - link twist
a (float) – kinematic - link length
sigma (int) – kinematic - 0 if revolute, 1 if prismatic
mdh (int) – kinematic - 0 if standard D&H, else 1
offset (float) – kinematic - joint variable offset
qlim (float ndarray(2)) – joint variable limits [min max]
flip (bool) – joint moves in opposite direction
m (float) – dynamic - link mass
r (float ndarray(3,1)) – dynamic - position of COM with respect to link frame
I (float ndarray(3,3)) – dynamic - inertia of link with respect to COM
Jm (float) – dynamic - motor inertia
B (float) – dynamic - motor viscous friction
Tc (float ndarray(2)) – dynamic - motor Coulomb friction (1x2 or 2x1)
G (float) – dynamic - gear ratio
- References
Robotics, Vision & Control, P. Corke, Springer 2011, Chap 7.
-
property
d
¶
-
property
alpha
¶
-
property
theta
¶
-
property
a
¶
-
property
sigma
¶
-
property
mdh
¶
-
property
offset
¶
-
property
qlim
¶
-
property
flip
¶
-
property
m
¶
-
property
r
¶
-
property
I
¶
-
property
Jm
¶
-
property
B
¶
-
property
Tc
¶
-
property
G
¶
-
dyn
()[source]¶ Show inertial properties of link
s = dyn() returns a string representation 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.
- Return s
The string representation of the link dynamics
- Rtype s
string
-
A
(q)[source]¶ Link transform matrix
T = 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)
- Parameters
q (float) – Joint angle (radians)
- Return T
link homogeneous transformation matrix
- Rtype T
float numpy.ndarray((4, 4))
- Notes
For a revolute joint the THETA parameter of the link is ignored, and q used instead.
For a prismatic joint the D parameter of the link is ignored, and q used instead.
The link offset parameter is added to Q before computation of the transformation matrix.
-
islimit
(q)[source]¶ Checks if the joint is exceeding a joint limit
- Returns
True if joint is exceeded
- Return type
bool
-
isrevolute
()[source]¶ Checks if the joint is of revolute type
- Returns
Ture if is revolute
- Return type
bool
-
isprismatic
()[source]¶ Checks if the joint is of prismatic type
- Returns
Ture if is prismatic
- Return type
bool
-
nofriction
(coulomb=True, viscous=False)[source]¶ l2 = nofriction(coulomb, viscous) copies the link and returns a link with the same parameters except, the Coulomb and/or viscous friction parameter to zero.
l2 = nofriction() as above except the the Coulomb parameter is set to zero.
- Parameters
coulomb (bool) – if True, will set the coulomb friction to 0
viscous (bool) – if True, will set the viscous friction to 0
-
friction
(qd)[source]¶ tau = friction(qd) Calculates the joint friction force/torque (n) for joint velocity qd (n). The friction model includes:
Viscous friction which is a linear function of velocity.
Coulomb friction which is proportional to sign(qd).
- Parameters
qd (float) – The joint velocity
- Return tau
the friction force/torque
- Rtype tau
float
- Notes
The friction value should be added to the motor output torque, it has a negative value when qd > 0.
The returned friction value is referred to the output of the gearbox.
The friction parameters in the Link object are referred to the motor.
Motor viscous friction is scaled up by G^2.
Motor Coulomb friction is scaled up by G.
The appropriate Coulomb friction value to use in the non-symmetric case depends on the sign of the joint velocity, not the motor velocity.
The absolute value of the gear ratio is used. Negative gear ratios are tricky: the Puma560 has negative gear ratio for joints 1 and 3.