8000 fix partial fkine · QR-Zhang/robotics-toolbox-python@e1d6d2c · GitHub
[go: up one dir, main page]

Skip to content

Commit e1d6d2c

Browse files
committed
fix partial fkine
1 parent bf8c2de commit e1d6d2c

File tree

2 files changed

+169
-101
lines changed

2 files changed

+169
-101
lines changed

roboticstoolbox/robot/ERobot.py

Lines changed: 1 addition & 101 deletions
Original file line numberDiff line numberDiff line change
@@ -1762,7 +1762,6 @@ def partial_fkine0(
17621762
n: int = 3,
17631763
end: Union[str, Link, Gripper, None] = None,
17641764
start: Union[str, Link, Gripper, None] = None,
1765-
tool: Union[ndarray, SE3, None] = None,
17661765
):
17671766
r"""
17681767
Manipulator Forward Kinematics nth Partial Derivative
@@ -1787,106 +1786,7 @@ def partial_fkine0(
17871786
Sequence, J. Haviland and P. Corke
17881787
"""
17891788

1790-
end, start, _ = self._get_limit_links(end, start)
1791-
1792-
def cross(a, b):
1793-
x = a[1] * b[2] - a[2] * b[1]
1794-
y = a[2] * b[0] - a[0] * b[2]
1795-
z = a[0] * b[1] - a[1] * b[0]
1796-
return array([x, y, z])
1797-
1798-
_, nl, _ = self.get_path(end, start)
1799-
1800-
J = self.jacob0(q, end=end, start=start)
1801-
H = self.hessian0(q, end=end, start=start, J0=J)
1802-
1803-
d = [J, H]
1804-
size = [6, nl, nl]
1805-
count = array([0, 0])
1806-
c = 2
1807-
1808-
def add_indices(indices, c):
1809-
total = len(indices * 2)
1810-
new_indices = []
1811-
1812-
for i in range(total):
1813-
j = i // 2
1814-
new_indices.append([])
1815-
new_indices[i].append(indices[j][0].copy())
1816-
new_indices[i].append(indices[j][1].copy())
1817-
1818-
# if even number
1819-
if i % 2 == 0:
1820-
new_indices[i][0].append(c)
1821-
# if odd number
1822-
else:
1823-
new_indices[i][1].append(c)
1824-
1825-
return new_indices
1826-
1827-
def add_pdi(pdi):
1828-
total = len(pdi * 2)
1829-
new_pdi = []
1830-
1831-
for i in range(total):
1832-
j = i // 2
1833-
new_pdi.append([])
1834-
new_pdi[i].append(pdi[j][0])
1835-
new_pdi[i].append(pdi[j][1])
1836-
1837-
# if even number
1838-
if i % 2 == 0:
1839-
new_pdi[i][0] += 1
1840-
# if odd number
1841-
else:
1842-
new_pdi[i][1] += 1
1843-
1844-
return new_pdi
1845-
1846-
# these are the indices used 6D47 for the hessian
1847-
indices = [[[1], [0]]]
1848-
1849-
# the are the pd indices used in the cross prods
1850-
pdi = [[0, 0]]
1851-
1852-
while len(d) != n:
1853-
size.append(nl)
1854-
count = concatenate((count, 0))
1855-
indices = add_indices(indices, c)
1856-
pdi = add_pdi(pdi)
1857-
c += 1
1858-
1859-
pd = zeros(size)
1860-
1861-
for i in range(nl**c):
1862-
1863-
rot = zeros(3)
1864-
trn = zeros(3)
1865-
1866-
for j in range(len(indices)):
1867-
pdr0 = d[pdi[j][0]]
1868-
pdr1 = d[pdi[j][1]]
1869-
1870-
idx0 = count[indices[j][0]]
1871-
idx1 = count[indices[j][1]]
1872-
1873-
rot += cross(pdr0[(slice(3, 6), *idx0)], pdr1[(slice(3, 6), *idx1)])
1874-
1875-
trn += cross(pdr0[(slice(3, 6), *idx0)], pdr1[(slice(0, 3), *idx1)])
1876-
1877-
pd[(slice(0, 3), *count)] = trn
1878-
pd[(slice(3, 6), *count)] = rot
1879-
1880-
count[0] += 1
1881-
for j in range(len(count)):
1882-
if count[j] == nl:
1883-
count[j] = 0
1884-
if j != len(count) - 1:
1885-
count[j + 1] += 1
1886-
1887-
d.append(pd)
1888-
1889-
return d[-1]
1789+
return self.ets(start, end).partial_fkine0(q, n=n)
18901790

18911791
def link_collision_damper(
18921792
self,

roboticstoolbox/robot/ETS.py

Lines changed: 168 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,9 @@
1919
min,
2020
max,
2121
where,
22+
cross,
23+
flip,
24+
concatenate,
2225
)
2326
from numpy.random import uniform
2427
from numpy.linalg import inv, det, cond, pinv, matrix_rank, svd, eig
@@ -1503,6 +1506,171 @@ def asada(robot, J, q, axes, **kwargs):
15031506
# else:
15041507
return w
15051508

1509+
def partial_fkine0(self, q: ArrayLike, n: int) -> ndarray:
1510+
r"""
1511+
Manipulator Forward Kinematics nth Partial Derivative
1512+
1513+
The manipulator Hessian tensor maps joint acceleration to end-effector
1514+
spatial acceleration, expressed in the ee frame. This
1515+
function calulcates this based on the ETS of the robot. One of Je or q
1516+
is required. Supply Je if already calculated to save computation time
1517+
1518+
:param q: The joint angles/configuration of the robot (Optional,
1519+
if not supplied will use the stored q values).
1520+
:type q: ArrayLike
1521+
:param end: the final link/Gripper which the Hessian represents
1522+
:param start: the first link which the Hessian represents
1523+
:param tool: a static tool transformation matrix to apply to the
1524+
end of end, defaults to None
1525+
1526+
:return: The nth Partial Derivative of the forward kinematics
1527+
1528+
:references:
1529+
- Kinematic Derivatives using the Elementary Transform
1530+
Sequence, J. Haviland and P. Corke
1531+
"""
1532+
1533+
# Calculate the Jacobian and Hessian
1534+
J = self.jacob0(q)
1535+
H = self.hessian0(q)
1536+
1537+
# A list of derivatives, starting with the jacobian and hessian
1538+
dT = [J, H]
1539+
1540+
# The tensor dimensions of the latest derivative
1541+
# Set to the current size of the Hessian
1542+
size = [self.n, 6, self.n]
1543+
1544+
# An array which keeps track of the index of the partial derivative
1545+
# we are calculating
1546+
# It stores the indices in the order: "j, k, l. m, n, o, ..."
1547+
# where count is extended to match oder of the partial derivative
1548+
count = array([0, 0])
1549+
1550+
# The order of derivative for which we are calculating
1551+
# The Hessian is the 2nd-order so we start with c = 2
1552+
c = 2
1553+
1554+
def add_indices(indices, c):
1555+
total = len(indices * 2)
1556+
new_indices = []
1557+
1558+
for i in range(total):
1559+
j = i // 2
1560+
new_indices.append([])
1561+
new_indices[i].append(indices[j][0].copy())
1562+
new_indices[i].append(indices[j][1].copy())
1563+
1564+
if i % 2 == 0:
1565+
# if even number
1566+
new_indices[i][0].append(c)
1567+
else:
1568+
# if odd number
1569+
new_indices[i][1].append(c)
1570+
1571+
return new_indices
1572+
1573+
def add_pdi(pdi):
1574+
total = len(pdi * 2)
1575+
new_pdi = []
1576+
1577+
for i in range(total):
1578+
j = i // 2
1579+
new_pdi.append([])
1580+
new_pdi[i].append(pdi[j][0])
1581+
new_pdi[i].append(pdi[j][1])
1582+
1583+
# if even number
1584+
if i % 2 == 0:
1585+
new_pdi[i][0] += 1
1586+
# if odd number
1587+
else:
1588+
new_pdi[i][1] += 1
1589+
1590+
return new_pdi
1591+
1592+
# these are the indices used for the hessian
1593+
indices = [[[1], [0]]]
1594+
1595+
# The partial derivative indices (pdi)
1596+
# the are the pd indices used in the cross products
1597+
pdi = [[0, 0]]
1598+
1599+
# The length of dT correspods to the number of derivatives we have calculated
1600+
while len(dT) != n:
1601+
1602+
# Add to the start of the tensor size list
1603+
size.insert(0, self.n)
1604+
1605+
# Add an axis to the count array
1606+
count = concatenate(([0], count))
1607+
1608+
# This variables corresponds to indices within the previous partial derivatives
1609+
# to be cross prodded
1610+
# The order is: "[j, k, l, m, n, o, ...]"
1611+
# Although, our partial derivatives have the order: pd[..., o, n, m, l, k, cartesian DoF, j]
1612+
# For example, consider the Hessian Tensor H[n, 6, n], the index H[k, :, j]. This corrsponds
1613+
# to the second partial derivative of the kinematics of joint j with respect to joint k.
1614+
indices = add_indices(indices, c)
1615+
1616+
# This variable corresponds to the indices in Td which corresponds to the
1617+
# partial derivatives we need to use
1618+
pdi = add_pdi(pdi)
1619+
1620+
c += 1
1621+
1622+
# Allocate our new partial derivative tensor
1623+
pd = zeros(size)
1624+
1625+
# We need to loop n^c times
1626+
# There are n^c columns to calculate
1627+
for _ in range(self.n**c):
1628+
1629+
# Allocate the rotation and translation components
1630+
rot = zeros(3)
1631+
trn = zeros(3)
1632+
1633+
# This loop calculates a single column ([trn, rot]) of the tensor for dT(x)
1634+
for j in range(len(indices)):
1635+
pdr0 = dT[pdi[j][0]]
1636+
pdr1 = dT[pdi[j][1]]
1637+
1638+
idx0 = count[indices[j][0]]
1639+
idx1 = count[indices[j][1]]
1640+
1641+
# This is a list of indices selecting the slices of the previous tensor
1642+
idx0_slices = flip(idx0[1:])
1643+
idx1_slices = flip(idx1[1:])
1644+
1645+
# This index selecting the column within the 2d slice of the previous tensor
1646+
idx0_n = idx0[0]
1647+
idx1_n = idx1[0]
1648+
1649+
# Use our indices to select the rotational column from pdr0 and pdr1
1650+
col0_rot = pdr0[(*idx0_slices, slice(3, 6), idx0_n)]
1651+
col1_rot = pdr1[(*idx1_slices, slice(3, 6), idx1_n)]
1652+
1653+
# Use our indices to select the translational column from pdr1
1654+
col1_trn = pdr1[(*idx1_slices, slice(0, 3), idx1_n)]
1655+
1656+
# Perform the cross product as described in the maths above
1657+
rot += cross(col0_rot, col1_rot)
1658+
trn += cross(col0_rot, col1_trn)
1659+
1660+
pd[(*flip(count[1:]), slice(0, 3), count[0])] = trn
1661+
pd[(*flip 8E94 (count[1:]), slice(3, 6), count[0])] = rot
1662+
1663+
count[0] += 1
1664+
for j in range(len(count)):
1665+
if count[j] == self.n:
1666+
count[j] = 0
1667+
if j != len(count) - 1:
1668+
count[j + 1] += 1
1669+
1670+
dT.append(pd)
1671+
1672+
return dT[-1]
1673+
15061674
def ik_lm_chan(
15071675
self,
15081676
Tep: Union[ndarray, SE3],

0 commit comments

Comments
 (0)
0