Skip to content

Commit a4009da

Browse files
committed
Fix kinova joint angles
1 parent f3e3edc commit a4009da

File tree

2 files changed

+134
-16
lines changed

2 files changed

+134
-16
lines changed

roboticstoolbox/examples/test.py

+132-15
Original file line numberDiff line numberDiff line change
@@ -2,24 +2,141 @@
22
import roboticstoolbox as rtb
33
import spatialmath as sm
44

5-
q0 = np.array(
6-
[
7-
-1.66441371,
8-
-1.20998727,
9-
1.04248366,
10-
-2.10222463,
11-
1.05097407,
12-
1.41173279,
13-
0.0053529,
14-
]
5+
# q0 = np.array(
6+
# [
7+
# -1.66441371,
8+
# -1.20998727,
9+
# 1.04248366,
10+
# -2.10222463,
11+
# 1.05097407,
12+
# 1.41173279,
13+
# 0.0053529,
14+
# ]
15+
# )
16+
17+
# tol = 1e-6
18+
19+
# panda = rtb.models.Panda().ets()
20+
21+
# Tep = panda.eval([0, -0.3, 0, -2.2, 0, 2.0, np.pi / 4])
22+
23+
# solver = rtb.IK_QP()
24+
25+
# sol = panda.ik_LM(Tep, tol=tol, q0=q0, method="chan")
26+
27+
robot = rtb.models.KinovaGen3()
28+
29+
glink = rtb.Link(
30+
rtb.ET.tz(0.12),
31+
name="gripper_link",
32+
m=0.831,
33+
r=[0, 0, 0.0473],
34+
parent=robot.links[-1],
1535
)
1636

17-
tol = 1e-6
37+
robot.links.append(glink)
38+
39+
40+
n = len(robot.links)
41+
42+
print(n)
43+
44+
# allocate intermediate variables
45+
Xup = sm.SE3.Alloc(n)
46+
Xtree = sm.SE3.Alloc(n)
47+
48+
# The body velocities, accelerations and forces
49+
v = sm.SpatialVelocity.Alloc(n)
50+
a = sm.SpatialAcceleration.Alloc(n)
51+
f = sm.SpatialForce.Alloc(n)
52+
53+
# The joint inertia
54+
I = sm.SpatialInertia.Alloc(n) # noqa: E741
55+
56+
# Joint motion subspace matrix
57+
s = []
58+
59+
q = robot.qr
60+
qd = np.zeros(n)
61+
qdd = np.zeros(n)
62+
63+
Q = np.zeros(n)
64+
65+
# for link in robot.links:
66+
# print()
67+
# print(link.name)
68+
# print(link.isjoint)
69+
# print(link.m)
70+
71+
# for link in robot.grippers[0].links:
72+
# print()
73+
# print(link.name)
74+
# print(link.isjoint)
75+
# print(link.m)
76+
77+
for i, link in enumerate(robot.links):
78+
79+
# Allocate the inertia
80+
I[i] = sm.SpatialInertia(link.m, link.r, link.I)
81+
82+
# Compute the link transform
83+
Xtree[i] = sm.SE3(link.Ts, check=False) # type: ignore
84+
85+
# Append the variable axis of the joint to s
86+
if link.v is not None:
87+
s.append(link.v.s)
88+
else:
89+
s.append(np.zeros(6))
90+
91+
a_grav = -sm.SpatialAcceleration([0, 0, 9.81])
92+
93+
# Forward recursion
94+
for i, link in enumerate(robot.links):
95+
96+
if link.jindex is None:
97+
qi = 0
98+
qdi = 0
99+
qddi = 0
100+
else:
101+
qi = q[link.jindex]
102+
qdi = qd[link.jindex]
103+
qddi = qdd[link.jindex]
104+
105+
vJ = sm.SpatialVelocity(s[i] * qdi)
106+
107+
# Transform from parent(j) to j
108+
if link.isjoint:
109+
Xup[i] = sm.SE3(link.A(qi)).inv()
110+
else:
111+
Xup[i] = sm.SE3(link.A()).inv()
112+
113+
if link.parent is None:
114+
v[i] = vJ
115+
a[i] = Xup[i] * a_grav + sm.SpatialAcceleration(s[i] * qddi)
116+
else:
117+
jp = link.parent.jindex # type: ignore
118+
v[i] = Xup[i] * v[i - 1] + vJ
119+
a[i] = Xup[i] * a[i - 1] + sm.SpatialAcceleration(s[i] * qddi) + v[i] @ vJ
120+
121+
f[i] = I[i] * a[i] + v[i] @ (I[i] * v[i])
122+
123+
# backward recursion
124+
for i in reversed(range(n)):
125+
126+
link = robot.links[i]
127+
128+
Q[i] = sum(f[i].A * s[i])
18129

19-
panda = rtb.models.Panda().ets()
130+
if link.parent is not None:
131+
f[i - 1] = f[i - 1] + Xup[i] * f[i]
20132

21-
Tep = panda.eval([0, -0.3, 0, -2.2, 0, 2.0, np.pi / 4])
133+
print(np.round(Q, 2))
22134

23-
solver = rtb.IK_QP()
24135

25-
sol = panda.ik_LM(Tep, tol=tol, q0=q0, method="chan")
136+
for link in robot.links:
137+
print()
138+
print(link.name)
139+
print(link.isjoint)
140+
print(link.m)
141+
print(link.r)
142+
print(link.I)

roboticstoolbox/models/URDF/KinovaGen3.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ def __init__(self):
4747
# self.qdlim = np.array([
4848
# 2.1750, 2.1750, 2.1750, 2.1750, 2.6100, 2.6100, 2.6100, 3.0, 3.0])
4949

50-
self.qr = np.array([np.pi, -0.3, 0, -1.6, 0, -1.0, np.pi / 2])
50+
self.qr = np.deg2rad([0.0, 15.0, 180.0, 230.0, 0.0, 55.0, 90.0])
5151
self.qz = np.zeros(7)
5252

5353
self.addconfiguration("qr", self.qr)
@@ -57,6 +57,7 @@ def __init__(self):
5757
if __name__ == "__main__": # pragma nocover
5858

5959
robot = KinovaGen3()
60+
robot.q = robot.qr
6061
print(robot)
6162

6263
from swift import Swift

0 commit comments

Comments
 (0)