Elementary transform sequence (ETS) models
Code author: Jesse Haviland
Elementary transforms are canonic rotations or translations about, or along, the x-, y- or z-axes. The amount of rotation or translation can be a constant or a variable. A variable amount corresponds to a joint.
Consider the example:
1>>> from roboticstoolbox import ET
2>>> ET.Rx(45, 'deg')
3ET.Rx(eta=0.7853981633974483)
4>>> ET.tz(0.75)
5ET.tz(eta=0.75)
6>>> e = ET.Rx(0.3) * ET.tz(0.75)
7>>> print(e)
8Rx(17.19°) ⊕ tz(0.75)
9>>> e.fkine([])
10SE3(array([[ 1. , 0. , 0. , 0. ],
11 [ 0. , 0.9553, -0.2955, -0.2216],
12 [ 0. , 0.2955, 0.9553, 0.7165],
13 [ 0. , 0. , 0. , 1. ]]))
In lines 2-5 we defined two elementary transforms. Line 2 defines a rotation of 45° about the x-axis, and line 4 defines a translation of 0.75m along the z-axis. Compounding them in line 6, the result is the two elementary transforms in a sequence - an elementary transform sequence (ETS). An ETS can be arbitrarily long.
Line 8 evaluates the forward kinematics of the sequence, substituting in values,
and the result is an SE(3) matrix encapsulated in an 4x4
numpy array.
The real power comes from having variable arguments to the elementary transforms as shown in this example where we define a simple two link planar manipulator.
1>>> from roboticstoolbox import ET
2>>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1)
3>>> print(e)
4Rz(q0) ⊕ tx(1) ⊕ Rz(q1) ⊕ tx(1)
5>>> len(e)
64
7>>> e[1:3]
8[ET.tx(eta=1.0), ET.Rz(jindex=1)]
9>>> e.fkine([0, 0])
10SE3(array([[1., 0., 0., 2.],
11 [0., 1., 0., 0.],
12 [0., 0., 1., 0.],
13 [0., 0., 0., 1.]]))
14>>> e.fkine([1.57, -1.57])
15SE3(array([[1. , 0. , 0. , 1.0008],
16 [0. , 1. , 0. , 1. ],
17 [0. , 0. , 1. , 0. ],
18 [0. , 0. , 0. , 1. ]]))
Line 2 succinctly describes the kinematics in terms of elementary transforms: a rotation around the z-axis by the first joint angle, then a translation in the x-direction, then a rotation around the z-axis by the second joint angle, and finally a translation in the x-direction.
Line 3 creates the elementary transform sequence, with variable transforms.
e
is a single object that encapsulates a list of elementary transforms, and list like
methods such as len
as well as indexing and slicing as shown in lines 5-8.
Lines 9-18 evaluate the sequence, and substitutes elements from the passed arrays as the joint variables.
This approach is general enough to be able to describe any serial-link robot manipulator. For a branched manipulator we can use ETS to describe the connections between every parent and child link pair.
The ETS inherits list-like properties and has methods like reverse
and pop
.
Reference:
A simple and systematic approach to assigning Denavit-Hartenberg parameters. Peter I. Corke, IEEE Transactions on Robotics, 23(3), pp 590-594, June 2007.
ETS - 3D
- class roboticstoolbox.robot.ETS.ETS(arg=None)[source]
Bases:
BaseETS
This class implements an elementary transform sequence (ETS) for 3D
An instance can contain an elementary transform (ET) or an elementary transform sequence (ETS). It has list-like properties by subclassing UserList, which means we can perform indexing, slicing pop, insert, as well as using it as an iterator over its values.
ETS()
an empty ETS listETS(et)
an ETS containing a single ETETS([et0, et1, et2])
an ETS consisting of three ET’s
- Parameters:
arg (
Union
[List
[Union
[ETS
,ET
]],List
[ET
],List
[ETS
],ET
,ETS
,None
]) – Function to compute ET value
Examples
>>> from roboticstoolbox import ETS, ET >>> e = ET.Rz(0.3) # a single ET, rotation about z >>> ets1 = ETS(e) >>> len(ets1) 1 >>> ets2 = ET.Rz(0.3) * ET.tx(2) # an ETS >>> len(ets2) # of length 2 2 >>> ets2[1] # an ET sliced from the ETS ET.tx(eta=2.0)
References
Haviland, and P. Corke. “Manipulator Differential Kinematics Part I:
Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
Haviland, and P. Corke. “Manipulator Differential Kinematics Part II:
Acceleration and Advanced Applications.” arXiv preprint arXiv:2207.01794 (2022).
See also
rx()
,ry()
,rz()
,tx()
,ty()
,tz()
- compile()[source]
Compile an ETS
Perform constant folding for faster evaluation. Consecutive constant ETs are compounded, leading to a constant ET which is denoted by
SE3
when displayed.- Returns:
optimised ETS
- Return type:
compile
Examples
>>> import roboticstoolbox as rtb >>> robot = rtb.models.ETS.Panda() >>> ets = robot.ets() >>> ets [ET.tz(eta=0.333), ET.Rz(jindex=0), ET.Rx(eta=-1.5707963267948966), ET.Rz(jindex=1), ET.Rx(eta=1.5707963267948966), ET.tz(eta=0.316), ET.Rz(jindex=2), ET.tx(eta=0.0825), ET.Rx(eta=1.5707963267948966), ET.Rz(jindex=3), ET.tx(eta=-0.0825), ET.Rx(eta=-1.5707963267948966), ET.tz(eta=0.384), ET.Rz(jindex=4), ET.Rx(eta=1.5707963267948966), ET.Rz(jindex=5), ET.tx(eta=0.088), ET.Rx(eta=1.5707963267948966), ET.tz(eta=0.107), ET.Rz(jindex=6), ET.tz(eta=0.10300000000000001), ET.Rz(eta=-0.7853981633974483)] >>> ets.compile() [ET.SE3(T=array([[1. , 0. , 0. , 0. ], [0. , 1. , 0. , 0. ], [0. , 0. , 1. , 0.333], [0. , 0. , 0. , 1. ]])), ET.Rz(jindex=0), ET.SE3(T=array([[ 1., 0., 0., 0.], [ 0., 0., 1., 0.], [ 0., -1., 0., 0.], [ 0., 0., 0., 1.]])), ET.Rz(jindex=1), ET.SE3(T=array([[ 1. , 0. , 0. , 0. ], [ 0. , 0. , -1. , -0.316], [ 0. , 1. , 0. , 0. ], [ 0. , 0. , 0. , 1. ]])), ET.Rz(jindex=2), ET.SE3(T=array([[ 1. , 0. , 0. , 0.0825], [ 0. , 0. , -1. , 0. ], [ 0. , 1. , 0. , 0. ], [ 0. , 0. , 0. , 1. ]])), ET.Rz(jindex=3), ET.SE3(T=array([[ 1. , 0. , 0. , -0.0825], [ 0. , 0. , 1. , 0.384 ], [ 0. , -1. , 0. , 0. ], [ 0. , 0. , 0. , 1. ]])), ET.Rz(jindex=4), ET.SE3(T=array([[ 1., 0., 0., 0.], [ 0., 0., -1., 0.], [ 0., 1., 0., 0.], [ 0., 0., 0., 1.]])), ET.Rz(jindex=5), ET.SE3(T=array([[ 1. , 0. , 0. , 0.088], [ 0. , 0. , -1. , -0.107], [ 0. , 1. , 0. , 0. ], [ 0. , 0. , 0. , 1. ]])), ET.Rz(jindex=6), ET.SE3(T=array([[ 0.7071, 0.7071, 0. , 0. ], [-0.7071, 0.7071, 0. , 0. ], [ 0. , 0. , 1. , 0.103 ], [ 0. , 0. , 0. , 1. ]]))]
See also
isconstant()
- insert(arg, i=-1)[source]
Insert value
Inserts an ET or ETS into the ET sequence. The inserted value is at position
i
.- Parameters:
- Return type:
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> f = ET.Ry() >>> e.insert(f, 2) >>> e [ET.Rz(jindex=0), ET.tx(eta=1.0), ET.Ry(), ET.Rz(jindex=1), ET.tx(eta=1.0)]
- fkine(q, base=None, tool=None, include_base=True)[source]
Forward kinematics
T = ets.fkine(q)
evaluates forward kinematics for the ets at joint configurationq
.Trajectory operation: If
q
has multiple rows (mxn), it is considered a trajectory and the result is anSE3
instance withm
values.- q
Joint coordinates
- base
A base transform applied before the ETS
- tool
tool transform, optional
- include_base
set to True if the base transform should be considered
- Return type:
SE3
- Returns:
The transformation matrix representing the pose of the end-effector
Examples
The following example makes a
panda
robot object, gets the ets, and solves for the forward kinematics at the listed configuration.>>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda().ets() >>> panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) SE3(array([[ 0.995 , -0. , 0.0998, 0.484 ], [-0. , -1. , 0. , 0. ], [ 0.0998, -0. , -0.995 , 0.4126], [ 0. , 0. , 0. , 1. ]]))
Notes
A tool transform, if provided, is incorporated into the result.
Works from the end-effector link to the base
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
- jacob0(q, tool=None)[source]
Manipulator geometric Jacobian in the base frame
robot.jacobo(q)
is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity expressed in the base frame.End-effector spatial velocity \(\nu = (v_x, v_y, v_z, \omega_x, \omega_y, \omega_z)^T\) is related to joint velocity by \({}^{E}\!\nu = \mathbf{J}_m(q) \dot{q}\).
- Parameters:
- Returns:
Manipulator Jacobian in the base frame
- Return type:
J0
Examples
The following example makes a
Puma560
robot object, and solves for the base-frame Jacobian at the zero joint angle configuration>>> import roboticstoolbox as rtb >>> puma = rtb.models.Puma560().ets() >>> puma.jacob0([0, 0, 0, 0, 0, 0]) array([[ 0.1295, -0.4854, -0.4854, -0. , -0.0533, 0. ], [ 0.4318, 0. , 0. , 0. , 0. , 0. ], [-0. , 0.4318, 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , -1. , -1. , 0. , -1. , 0. ], [ 1. , 0. , 0. , 1. , 0. , 1. ]])
Notes
- This is the geometric Jacobian as described in texts by
Corke, Spong etal., Siciliano etal. The end-effector velocity is described in terms of translational and angular velocity, not a velocity twist as per the text by Lynch & Park.
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
- jacobe(q, tool=None)[source]
Manipulator geometric Jacobian in the end-effector frame
robot.jacobe(q)
is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity expressed in theend
frame.End-effector spatial velocity \(\nu = (v_x, v_y, v_z, \omega_x, \omega_y, \omega_z)^T\) is related to joint velocity by \({}^{E}\!\nu = \mathbf{J}_m(q) \dot{q}\).
- Parameters:
q (
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
]]) – Joint coordinate vectorend – the particular link or gripper whose velocity the Jacobian describes, defaults to the end-effector if only one is present
start – the link considered as the base frame, defaults to the robots’s base frame
tool (
Union
[ndarray
,SE3
,None
]) – a static tool transformation matrix to apply to the end of end, defaults to None
- Returns:
Manipulator Jacobian in the
end
frame- Return type:
Je
Examples
The following example makes a
Puma560
robot object, and solves for the end-effector frame Jacobian at the zero joint angle configuration>>> import roboticstoolbox as rtb >>> puma = rtb.models.Puma560().ets() >>> puma.jacobe([0, 0, 0, 0, 0, 0]) array([[ 0.1295, -0.4854, -0.4854, -0. , -0.0533, 0. ], [ 0.4318, 0. , 0. , 0. , 0. , 0. ], [-0. , 0.4318, 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , -1. , -1. , 0. , -1. , 0. ], [ 1. , 0. , 0. , 1. , 0. , 1. ]])
Notes
- This is the geometric Jacobian as described in texts by
Corke, Spong etal., Siciliano etal. The end-effector velocity is described in terms of translational and angular velocity, not a velocity twist as per the text by Lynch & Park.
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
- hessian0(q=None, J0=None, tool=None)[source]
Manipulator Hessian
The manipulator Hessian tensor maps joint acceleration to end-effector spatial acceleration, expressed in the base frame. This function calulcates this based on the ETS of the robot. One of J0 or q is required. Supply J0 if already calculated to save computation time
- Parameters:
q (
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
],None
]) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).J0 (
Optional
[ndarray
]) – The manipulator Jacobian in the base frametool (
Union
[ndarray
,SE3
,None
]) – a static tool transformation matrix to apply to the end of end, defaults to None
- Returns:
The manipulator Hessian in the base frame
- Return type:
h0
Synopsis
This method computes the manipulator Hessian in the base frame. If we take the time derivative of the differential kinematic relationship .. math:
\nu &= \mat{J}(\vec{q}) \dvec{q} \\ \alpha &= \dmat{J} \dvec{q} + \mat{J} \ddvec{q}
where .. math:
\dmat{J} = \mat{H} \dvec{q}
and \(\mat{H} \in \mathbb{R}^{6\times n \times n}\) is the Hessian tensor.
The elements of the Hessian are .. math:
\mat{H}_{i,j,k} = \frac{d^2 u_i}{d q_j d q_k}
where \(u = \{t_x, t_y, t_z, r_x, r_y, r_z\}\) are the elements of the spatial velocity vector.
Similarly, we can write .. math:
\mat{J}_{i,j} = \frac{d u_i}{d q_j}
Examples
The following example makes a
Panda
robot object, and solves for the base frame Hessian at the given joint angle configuration>>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda().ets() >>> panda.hessian0([0, -0.3, 0, -2.2, 0, 2, 0.7854]) array([[[-0.484 , -0. , -0.486 , -0. , -0.1547, 0. , -0. ], [ 0. , 0.0796, 0. , 0.2466, 0. , 0.2006, 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , -1. , -0. , 1. , 0. , 1. , 0. ], [ 0. , -0. , -0.2955, -0. , 0.9463, -0. , 0.0998], [ 0. , 0. , -0. , -0. , 0. , -0. , 0. ]], [[-0. , -0.484 , -0. , 0.4986, -0. , 0.1086, 0. ], [ 0.0796, 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , -0.0796, -0. , -0.2466, -0. , -0.2006, -0. ], [ 0. , 0. , 0.9553, 0. , -0.3233, 0. , -0.995 ], [ 0. , 0. , -0. , -0. , 0. , -0. , 0. ], [ 0. , 0. , 0.2955, 0. , -0.9463, 0. , -0.0998]], [[-0.486 , -0. , -0.4643, -0. , -0.1478, 0. , 0. ], [ 0. , 0. , 0. , 0.383 , 0. , 0.2237, 0. ], [ 0. , -0. , -0.1436, -0. , -0.0457, -0. , -0. ], [ 0. , 0. , 0. , 0.9553, 0. , 0.9553, 0. ], [ 0. , 0. , 0. , -0. , 0.8085, -0. , -0.1987], [ 0. , 0. , 0. , 0.2955, 0. , 0.2955, 0. ]], [[-0. , 0.4986, -0. , -0.4986, 0. , -0.1086, -0. ], [ 0.2466, 0. , 0.383 , 0. , 0. , 0. , 0. ], [ 0. , -0.2466, -0. , 0.2466, 0. , 0.2006, 0. ], [ 0. , 0. , 0. , 0. , 0.3233, 0. , 0.995 ], [ 0. , 0. , 0. , 0. , 0. , 0. , -0. ], [ 0. , 0. , 0. , 0. , 0.9463, 0. , 0.0998]], [[-0.1547, -0. , -0.1478, 0. , 0.05 , -0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , -0.1676, -0. ], [ 0. , -0. , -0.0457, 0. , 0.1464, 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , -0.3233, 0. ], [ 0. , 0. , 0. , 0. , 0. , -0. , 0.9093], [ 0. , 0. , 0. , 0. , 0. , -0.9463, -0. ]], [[ 0. , 0.1086, 0. , -0.1086, -0. , -0.1086, -0. ], [ 0.2006, 0. , 0.2237, 0. , -0.1676, 0. , 0. ], [ 0. , -0.2006, -0. , 0.2006, 0. , 0.2006, 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0.995 ], [ 0. , 0. , 0. , 0. , 0. , 0. , -0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0.0998]], [[-0. , 0. , 0. , -0. , 0. , -0. , 0. ], [ 0. , 0. , 0. , 0. , -0. , 0. , -0. ], [ 0. , -0. , -0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ]]])
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part II: Acceleration and Advanced Applications.” arXiv preprint arXiv:2207.01794 (2022).
- hessiane(q=None, Je=None, tool=None)[source]
Manipulator Hessian
The manipulator Hessian tensor maps joint acceleration to end-effector spatial acceleration, expressed in the end-effector coordinate frame. This function calulcates this based on the ETS of the robot. One of J0 or q is required. Supply J0 if already calculated to save computation time
- Parameters:
q (
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
],None
]) – The joint angles/configuration of the robot (Optional, if not supplied will use the stored q values).J0 – The manipulator Jacobian in the end-effector frame
tool (
Union
[ndarray
,SE3
,None
]) – a static tool transformation matrix to apply to the end of end, defaults to None
- Returns:
The manipulator Hessian in end-effector frame
- Return type:
he
Synopsis
This method computes the manipulator Hessian in the end-effector frame. If we take the time derivative of the differential kinematic relationship .. math:
\nu &= \mat{J}(\vec{q}) \dvec{q} \\ \alpha &= \dmat{J} \dvec{q} + \mat{J} \ddvec{q}
where .. math:
\dmat{J} = \mat{H} \dvec{q}
and \(\mat{H} \in \mathbb{R}^{6\times n \times n}\) is the Hessian tensor.
The elements of the Hessian are .. math:
\mat{H}_{i,j,k} = \frac{d^2 u_i}{d q_j d q_k}
where \(u = \{t_x, t_y, t_z, r_x, r_y, r_z\}\) are the elements of the spatial velocity vector.
Similarly, we can write .. math:
\mat{J}_{i,j} = \frac{d u_i}{d q_j}
Examples
The following example makes a
Panda
robot object, and solves for the end-effector frame Hessian at the given joint angle configuration>>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda().ets() >>> panda.hessiane([0, -0.3, 0, -2.2, 0, 2, 0.7854]) array([[[-0.4816, -0. , -0.4835, -0. , -0.1539, -0. , 0. ], [ 0. , -0.0796, 0. , -0.2466, 0. , -0.2006, 0. ], [-0.0483, -0. , -0.0485, -0. , -0.0154, -0. , 0. ], [ 0. , -0.995 , 0. , 0.995 , -0. , 0.995 , -0. ], [ 0. , 0. , 0.2955, -0. , -0.9463, -0. , -0.0998], [ 0. , -0.0998, 0. , 0.0998, -0. , 0.0998, 0. ]], [[-0. , -0.4896, -0. , 0.4715, -0. , 0.088 , 0. ], [-0.0796, 0. , 0. , -0. , 0. , -0. , 0. ], [-0. , 0.0309, 0. , 0.2952, 0. , 0.2104, -0. ], [ 0. , 0. , 0.9801, 0. , -0.4161, 0. , -1. ], [ 0. , 0. , -0. , -0. , 0. , -0. , 0. ], [ 0. , 0. , -0.1987, -0. , 0.9093, -0. , 0. ]], [[-0.4835, -0. , -0.4763, -0. , -0.1516, -0. , 0. ], [ 0. , 0. , 0. , -0.383 , 0. , -0.2237, 0. ], [-0.0485, 0. , 0.0965, -0. , 0.0307, -0. , 0. ], [ 0. , 0. , 0. , 0.9801, -0. , 0.9801, 0. ], [ 0. , 0. , 0. , -0. , -0.8085, -0. , 0.1987], [ 0. , 0. , 0. , -0.1987, -0. , -0.1987, -0. ]], [[-0. , 0.4715, -0. , -0.4715, 0. , -0.088 , 0. ], [-0.2466, -0. , -0.383 , 0. , -0. , 0. , -0. ], [-0. , 0.2952, -0. , -0.2952, -0. , -0.2104, 0. ], [ 0. , 0. , 0. , 0. , 0.4161, 0. , 1. ], [ 0. , 0. , 0. , 0. , -0. , 0. , -0. ], [ 0. , 0. , 0. , 0. , -0.9093, 0. , 0. ]], [[-0.1539, -0. , -0.1516, 0. , 0.0644, 0. , -0. ], [ 0. , 0. , 0. , -0. , -0. , 0.1676, -0. ], [-0.0154, 0. , 0.0307, -0. , -0.1407, -0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , -0.4161, -0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , -0.9093], [ 0. , 0. , 0. , 0. , 0. , 0.9093, 0. ]], [[-0. , 0.088 , -0. , -0.088 , 0. , -0.088 , 0. ], [-0.2006, -0. , -0.2237, 0. , 0.1676, 0. , -0. ], [-0. , 0.2104, -0. , -0.2104, -0. , -0.2104, 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 1. ], [ 0. , 0. , 0. , 0. , 0. , 0. , -0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ]], [[ 0. , 0. , 0. , 0. , -0. , 0. , 0. ], [ 0. , 0. , 0. , -0. , -0. , -0. , -0. ], [ 0. , -0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ], [ 0. , 0. , 0. , 0. , 0. , 0. , 0. ]]])
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part II: Acceleration and Advanced Applications.” arXiv preprint arXiv:2207.01794 (2022).
- __str__(q=None)
Pretty prints the ETS
q
controls how the joint variables are displayed:- None, format depends on number of joint variables
one, display joint variable as q
more, display joint variables as q0, q1, …
if a joint index was provided, use this value
“”, display all joint variables as empty parentheses
()
“θ”, display all joint variables as
(θ)
format string with passed joint variables
(j, j+1)
, so “θ{0}” would display joint variables as θ0, θ1, … while “θ{1}” would display joint variables as θ1, θ2, …j
is either the joint index, if provided, otherwise a sequential value.
- Parameters:
q (
Optional
[str
]) – control how joint variables are displayed- Returns:
Pretty printed ETS
- Return type:
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() >>> print(e[:2]) [ET.Rz(jindex=0), ET.tx(eta=1.0)] >>> print(e) Rz(q0) ⊕ tx(1) ⊕ Rz(q1) >>> print(e.__str__("")) Rz() ⊕ tx(1) ⊕ Rz() >>> print(e.__str__("θ{0}")) # numbering from 0 Rz(θ0) ⊕ tx(1) ⊕ Rz(θ1) >>> print(e.__str__("θ{1}")) # numbering from 1 Rz(θ1) ⊕ tx(1) ⊕ Rz(θ2) >>> # explicit joint indices >>> e = ET.Rz(jindex=3) * ET.tx(1) * ET.Rz(jindex=4) >>> print(e) Rz(q3) ⊕ tx(1) ⊕ Rz(q4) >>> print(e.__str__("θ{0}")) Rz(θ3) ⊕ tx(1) ⊕ Rz(θ4)
Angular parameters are converted to degrees, except if they are symbolic.
>>> from roboticstoolbox import ET >>> from spatialmath.base import symbol >>> theta, d = symbol('theta, d') >>> e = ET.Rx(theta) * ET.tx(2) * ET.Rx(45, 'deg') * ET.Ry(0.2) * ET.ty(d) >>> str(e) 'Rx(theta) ⊕ tx(2) ⊕ Rx(45°) ⊕ Ry(11.46°) ⊕ ty(d)'
- __repr__()
Return repr(self).
- __getitem__(i)
Index or slice an ETS
- Parameters:
i – the index or slince
- Returns:
Elementary transform
- Return type:
et
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e[0] ET.Rz(jindex=0) >>> e[1] ET.tx(eta=1.0) >>> e[1:3] [ET.tx(eta=1.0), ET.Rz(jindex=1)]
- property n: int
Number of joints
Counts the number of joints in the ETS.
- Returns:
the number of joints in the ETS
- Return type:
n
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rx() * ET.tx(1) * ET.tz() >>> e.n 2
See also
- property m: int
Number of transforms
Counts the number of transforms in the ETS.
- Returns:
the number of transforms in the ETS
- Return type:
m
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rx() * ET.tx(1) * ET.tz() >>> e.m 3
- property structure: str
Joint structure string
A string comprising the characters ‘R’ or ‘P’ which indicate the types of joints in order from left to right.
- Returns:
A string indicating the joint types
- Return type:
structure
Examples
>>> from roboticstoolbox import ET >>> e = ET.tz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e.structure 'PR'
- joints()
Get a list of the variable ETs with this ETS
- Returns:
list of ETs that are joints
- Return type:
joints
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e.joints() [ET.Rz(jindex=0), ET.Rz(jindex=1)]
- split()
Split ETS into link segments
- Returns:
a list of ETS, each one, apart from the last, ends with a variable ET.
- Return type:
split
- inv()
Inverse of ETS
The inverse of a given ETS. It is computed as the inverse of the individual ETs in the reverse order.
\[(\mathbf{E}_0, \mathbf{E}_1 \cdots \mathbf{E}_{n-1} )^{-1} = (\mathbf{E}_{n-1}^{-1}, \mathbf{E}_{n-2}^{-1} \cdots \mathbf{E}_0^{-1}{n-1} )\]- Returns:
Inverse of the ETS
- Return type:
inv
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz(jindex=2) * ET.tx(1) * ET.Rx(jindex=3,flip=True) * ET.tx(1) >>> print(e) Rz(q2) ⊕ tx(1) ⊕ Rx(-q3) ⊕ tx(1) >>> print(e.inv()) tx(-1) ⊕ Rx(q3) ⊕ tx(-1) ⊕ Rz(-q2)
Notes
- It is essential to use explicit joint indices to account for
the reversed order of the transforms.
ETS - 2D
- class roboticstoolbox.robot.ETS.ETS2(arg=None)[source]
Bases:
BaseETS
This class implements an elementary transform sequence (ETS) for 2D
- Parameters:
arg (
Union
[List
[Union
[ETS2
,ET2
]],List
[ET2
],List
[ETS2
],ET2
,ETS2
,None
]) – Function to compute ET value
An instance can contain an elementary transform (ET) or an elementary transform sequence (ETS). It has list-like properties by subclassing UserList, which means we can perform indexing, slicing pop, insert, as well as using it as an iterator over its values.
ETS()
an empty ETS listET2.XY(η)
is a constant elementary transformET2.XY(η, 'deg')
as above but the angle is expressed in degreesET2.XY()
is a joint variable, the value is left free until evaluation timeET2.XY(j=J)
as above but the joint index is explicitly given, this might correspond to the joint number of a multi-joint robot.ET2.XY(flip=True)
as above but the joint moves in the opposite sense
where
XY
is one ofR
,tx
,ty
.Example
Traceback (most recent call last): File "<input>", line 1, in <module> AttributeError: type object 'ETS2' has no attribute 'R' Traceback (most recent call last): File "<input>", line 1, in <module> NameError: name 'e' is not defined Traceback (most recent call last): File "<input>", line 1, in <module> NameError: name 'e' is not defined
- References:
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
- Seealso:
r()
,tx()
,ty()
- __str__(q=None)
Pretty prints the ETS
q
controls how the joint variables are displayed:- None, format depends on number of joint variables
one, display joint variable as q
more, display joint variables as q0, q1, …
if a joint index was provided, use this value
“”, display all joint variables as empty parentheses
()
“θ”, display all joint variables as
(θ)
format string with passed joint variables
(j, j+1)
, so “θ{0}” would display joint variables as θ0, θ1, … while “θ{1}” would display joint variables as θ1, θ2, …j
is either the joint index, if provided, otherwise a sequential value.
- Parameters:
q (
Optional
[str
]) – control how joint variables are displayed- Returns:
Pretty printed ETS
- Return type:
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() >>> print(e[:2]) [ET.Rz(jindex=0), ET.tx(eta=1.0)] >>> print(e) Rz(q0) ⊕ tx(1) ⊕ Rz(q1) >>> print(e.__str__("")) Rz() ⊕ tx(1) ⊕ Rz() >>> print(e.__str__("θ{0}")) # numbering from 0 Rz(θ0) ⊕ tx(1) ⊕ Rz(θ1) >>> print(e.__str__("θ{1}")) # numbering from 1 Rz(θ1) ⊕ tx(1) ⊕ Rz(θ2) >>> # explicit joint indices >>> e = ET.Rz(jindex=3) * ET.tx(1) * ET.Rz(jindex=4) >>> print(e) Rz(q3) ⊕ tx(1) ⊕ Rz(q4) >>> print(e.__str__("θ{0}")) Rz(θ3) ⊕ tx(1) ⊕ Rz(θ4)
Angular parameters are converted to degrees, except if they are symbolic.
>>> from roboticstoolbox import ET >>> from spatialmath.base import symbol >>> theta, d = symbol('theta, d') >>> e = ET.Rx(theta) * ET.tx(2) * ET.Rx(45, 'deg') * ET.Ry(0.2) * ET.ty(d) >>> str(e) 'Rx(theta) ⊕ tx(2) ⊕ Rx(45°) ⊕ Ry(11.46°) ⊕ ty(d)'
- __repr__()
Return repr(self).
- __getitem__(i)
Index or slice an ETS
- Parameters:
i – the index or slince
- Returns:
Elementary transform
- Return type:
et
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e[0] ET.Rz(jindex=0) >>> e[1] ET.tx(eta=1.0) >>> e[1:3] [ET.tx(eta=1.0), ET.Rz(jindex=1)]
- property n: int
Number of joints
Counts the number of joints in the ETS.
- Returns:
the number of joints in the ETS
- Return type:
n
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rx() * ET.tx(1) * ET.tz() >>> e.n 2
See also
- property m: int
Number of transforms
Counts the number of transforms in the ETS.
- Returns:
the number of transforms in the ETS
- Return type:
m
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rx() * ET.tx(1) * ET.tz() >>> e.m 3
- property structure: str
Joint structure string
A string comprising the characters ‘R’ or ‘P’ which indicate the types of joints in order from left to right.
- Returns:
A string indicating the joint types
- Return type:
structure
Examples
>>> from roboticstoolbox import ET >>> e = ET.tz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e.structure 'PR'
- joints()
Get a list of the variable ETs with this ETS
- Returns:
list of ETs that are joints
- Return type:
joints
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz() * ET.tx(1) * ET.Rz() * ET.tx(1) >>> e.joints() [ET.Rz(jindex=0), ET.Rz(jindex=1)]
- split()
Split ETS into link segments
- Returns:
a list of ETS, each one, apart from the last, ends with a variable ET.
- Return type:
split
- inv()
Inverse of ETS
The inverse of a given ETS. It is computed as the inverse of the individual ETs in the reverse order.
\[(\mathbf{E}_0, \mathbf{E}_1 \cdots \mathbf{E}_{n-1} )^{-1} = (\mathbf{E}_{n-1}^{-1}, \mathbf{E}_{n-2}^{-1} \cdots \mathbf{E}_0^{-1}{n-1} )\]- Returns:
Inverse of the ETS
- Return type:
inv
Examples
>>> from roboticstoolbox import ET >>> e = ET.Rz(jindex=2) * ET.tx(1) * ET.Rx(jindex=3,flip=True) * ET.tx(1) >>> print(e) Rz(q2) ⊕ tx(1) ⊕ Rx(-q3) ⊕ tx(1) >>> print(e.inv()) tx(-1) ⊕ Rx(q3) ⊕ tx(-1) ⊕ Rz(-q2)
Notes
- It is essential to use explicit joint indices to account for
the reversed order of the transforms.
- compile()[source]
Compile an ETS2
- Return type:
- Returns:
optimised ETS2
Perform constant folding for faster evaluation. Consecutive constant ETs are compounded, leading to a constant ET which is denoted by
SE3
when displayed.- Seealso:
isconstant()
- insert(arg, i=-1)[source]
Insert value
- Parameters:
- Return type:
Inserts an ET or ETS into the ET sequence. The inserted value is at position
i
.Example:
>>> from roboticstoolbox import ET2 >>> e = ET2.R() * ET2.tx(1) * ET2.R() * ET2.tx(1) >>> f = ET2.R() >>> e.insert(f, 2) >>> e [ET2.R(jindex=0), ET2.tx(eta=1.0), ET2.R(), ET2.R(jindex=1), ET2.tx(eta=1.0)]
- fkine(q, base=None, tool=None, include_base=True)[source]
Forward kinematics :type q:
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
]] :param q: Joint coordinates :type q: ArrayLike :type base:Union
[ndarray
,SE2
,None
] :param base: base transform, optional :type tool:Union
[ndarray
,SE2
,None
] :param tool: tool transform, optional- Return type:
SE2
- Returns:
The transformation matrix representing the pose of the end-effector
T = ets.fkine(q)
evaluates forward kinematics for the robot at joint configurationq
.
Trajectory operation: If
q
has multiple rows (mxn), it is considered a trajectory and the result is anSE2
instance withm
values. .. note:- The robot's base tool transform, if set, is incorporated into the result. - A tool transform, if provided, is incorporated into the result. - Works from the end-effector link to the base
- References:
Kinematic Derivatives using the Elementary Transform Sequence, J. Haviland and P. Corke
- jacobe(q)[source]
Jacobian in base frame
- Parameters:
q (ArrayLike) – joint coordinates
- Returns:
Jacobian matrix
jacobe(q)
is the manipulator Jacobian matrix which maps joint velocity to end-effector spatial velocity.End-effector spatial velocity \(\nu = (v_x, v_y, v_z, \omega_x, \omega_y, \omega_z)^T\) is related to joint velocity by \({}^{e}\nu = {}^{e}\mathbf{J}_0(q) \dot{q}\).
- Seealso:
jacob()
,hessian0()