Skip to content

Commit a53c864

Browse files
committed
Potential RNE fix for #368 and #236, for robot's with static joints
1 parent a4009da commit a53c864

File tree

1 file changed

+97
-45
lines changed

1 file changed

+97
-45
lines changed

roboticstoolbox/robot/Robot.py

+97-45
Original file line numberDiff line numberDiff line change
@@ -1740,10 +1740,10 @@ def rne(
17401740
"""
17411741

17421742
n = self.n
1743+
# n = len(self.links)
17431744

17441745
# allocate intermediate variables
17451746
Xup = SE3.Alloc(n)
1746-
Xtree = SE3.Alloc(n)
17471747

17481748
v = SpatialVelocity.Alloc(n)
17491749
a = SpatialAcceleration.Alloc(n)
@@ -1755,81 +1755,133 @@ def rne(
17551755
q = getmatrix(q, (None, None))
17561756
qd = getmatrix(qd, (None, None))
17571757
qdd = getmatrix(qdd, (None, None))
1758-
l, _ = q.shape # type: ignore
1758+
l, _ = q.shape
17591759

17601760
if symbolic: # pragma: nocover
17611761
Q = np.empty((l, n), dtype="O") # joint torque/force
17621762
else:
17631763
Q = np.empty((l, n)) # joint torque/force
17641764

1765-
# TODO Should the dynamic parameters of static links preceding joint be
1766-
# somehow merged with the joint?
1765+
qn = np.empty((l, n))
1766+
qdn = np.empty((l, n))
1767+
qddn = np.empty((l, n))
17671768

1768-
# A temp variable to handle static joints
1769-
Ts = SE3()
1769+
link_groups: List[List[int]] = []
17701770

1771-
# A counter through joints
1772-
j = 0
1771+
# Group links together based on whether they are joints or not
1772+
# Static links are grouped with the first joint encountered
1773+
current_group = []
1774+
for i, link in enumerate(self.links):
1775+
current_group.append(i)
1776+
1777+
# Break after adding the first link
1778+
if link.isjoint:
1779+
link_groups.append(current_group)
1780+
current_group = []
1781+
1782+
# Make some intermediate variables
1783+
for i, group in enumerate(link_groups):
1784+
I_int = SpatialInertia()
1785+
1786+
for idx in group:
1787+
link = self.links[idx]
1788+
1789+
I_int = I_int + SpatialInertia(m=link.m, r=link.r)
1790+
1791+
if link.v is not None:
1792+
s.append(link.v.s)
1793+
1794+
I[i] = I_int
1795+
1796+
if gravity is None:
1797+
a_grav = -SpatialAcceleration(self.gravity)
1798+
else: # pragma nocover
1799+
a_grav = -SpatialAcceleration(gravity)
1800+
1801+
# For the following, v, a, f, I, s, Xup are all lists of length n
1802+
# where the indices correspond to the index of the group within
1803+
# link_groups
1804+
# As always, q, qd, qdd are lists of length n, where indices correspond
1805+
# to the jindex of the joint, which will be the last link in the group
1806+
# within link_groups
17731807

17741808
for k in range(l):
17751809
qk = q[k, :]
17761810
qdk = qd[k, :]
17771811
qddk = qdd[k, :]
17781812

1779-
# initialize intermediate variables
1780-
for link in self.links:
1781-
if link.isjoint:
1782-
I[j] = SpatialInertia(m=link.m, r=link.r)
1783-
if symbolic and link.Ts is None: # pragma: nocover
1784-
Xtree[j] = SE3(np.eye(4, dtype="O"), check=False)
1785-
elif link.Ts is not None:
1786-
Xtree[j] = Ts * SE3(link.Ts, check=False)
1813+
# forward recursion
1814+
for j, group in enumerate(link_groups):
17871815

1788-
if link.v is not None:
1789-
s.append(link.v.s)
1816+
# The joint is the last link in the group
1817+
joint = self.links[group[-1]]
1818+
jindex = joint.jindex
17901819

1791-
# Increment the joint counter
1792-
j += 1
1820+
vJ = SpatialVelocity(s[j] * qdk[jindex])
17931821

1794-
# Reset the Ts tracker
1795-
Ts = SE3()
1796-
else: # pragma nocover
1797-
# TODO Keep track of inertia and transform???
1798-
if link.Ts is not None:
1799-
Ts *= SE3(link.Ts, check=False)
1822+
# transform from parent(j) to j
1823+
Xup_int = SE3()
1824+
for idx in group:
1825+
link = self.links[idx]
18001826

1801-
if gravity is None:
1802-
a_grav = -SpatialAcceleration(self.gravity)
1803-
else: # pragma nocover
1804-
a_grav = -SpatialAcceleration(gravity)
1827+
if link.isjoint and link.jindex is not None:
1828+
Xup_int = Xup_int * SE3(link.A(qk[link.jindex]))
1829+
else:
1830+
Xup_int = Xup_int * SE3(link.A())
18051831

1806-
# forward recursion
1807-
for j in range(0, n):
1808-
vJ = SpatialVelocity(s[j] * qdk[j])
1832+
Xup[j] = Xup_int.inv()
18091833

1810-
# transform from parent(j) to j
1811-
Xup[j] = SE3(self.links[j].A(qk[j])).inv()
1834+
# The first link in the group
1835+
first_link = self.links[group[0]]
18121836

1813-
if self.links[j].parent is None:
1837+
if first_link.parent is None:
18141838
v[j] = vJ
1815-
a[j] = Xup[j] * a_grav + SpatialAcceleration(s[j] * qddk[j])
1839+
a[j] = Xup[j] * a_grav + SpatialAcceleration(s[j] * qddk[jindex])
18161840
else:
1817-
jp = self.links[j].parent.jindex # type: ignore
1818-
v[j] = Xup[j] * v[jp] + vJ
1841+
# The index of `link`s parent within self.links
1842+
parent_idx = self.links.index(first_link.parent)
1843+
1844+
# The index of the group that the parent link is in
1845+
group_idx = [
1846+
i for i, group in enumerate(link_groups) if parent_idx in group
1847+
][0]
1848+
1849+
v[j] = Xup[j] * v[group_idx] + vJ
18191850
a[j] = (
1820-
Xup[j] * a[jp] + SpatialAcceleration(s[j] * qddk[j]) + v[j] @ vJ
1851+
Xup[j] * a[group_idx]
1852+
+ SpatialAcceleration(s[j] * qddk[jindex])
1853+
+ v[j] @ vJ
18211854
)
18221855

18231856
f[j] = I[j] * a[j] + v[j] @ (I[j] * v[j])
18241857

1825-
# backward recursion
1826-
for j in reversed(range(0, n)):
1858+
# Backward recursion
1859+
for j in reversed(range(n)):
1860+
1861+
group = link_groups[j]
1862+
joint = self.links[group[-1]]
1863+
first_link = self.links[group[0]]
1864+
# link = self.links[j]
1865+
18271866
# next line could be dot(), but fails for symbolic arguments
18281867
Q[k, j] = sum(f[j].A * s[j])
18291868

1830-
if self.links[j].parent is not None:
1831-
jp = self.links[j].parent.jindex # type: ignore
1832-
f[jp] = f[jp] + Xup[j] * f[j]
1869+
if first_link.parent is not None:
1870+
1871+
# The index of `link`s parent within self.links
1872+
parent_idx = self.links.index(first_link.parent)
1873+
1874+
# The index of the group that the parent link is in
1875+
group_idx = [
1876+
i for i, group in enumerate(link_groups) if parent_idx in group
1877+
][0]
1878+
1879+
f[group_idx] = f[group_idx] + Xup[j] * f[j]
1880+
1881+
# The current Q has the length equal to the number of links within the robot
1882+
# rather than the number of joints. We need to remove the static links
1883+
# from the Q array
1884+
# joint_idx = [i for i, link in enumerate(self.links) if link.isjoint]
18331885

18341886
if l == 1:
18351887
return Q[0]

0 commit comments

Comments
 (0)