Skip to content

Commit 733f395

Browse files
committed
experiments
1 parent ae2e830 commit 733f395

File tree

10 files changed

+1403
-179
lines changed

10 files changed

+1403
-179
lines changed

examples/bookshelf.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -235,7 +235,7 @@ def link_calc(link, col, ob, q):
235235
dp = nh @ ob.v
236236
l_Ain = np.zeros((1, 13))
237237
l_Ain[0, :n] = nh @ Je
238-
l_bin = (1 * (d - ds) / (di - ds)) + dp
238+
l_bin = (5 * (d - ds) / (di - ds)) + dp
239239
else:
240240
l_Ain = None
241241
l_bin = None
@@ -271,7 +271,7 @@ def servo(q0, q1, it):
271271
eTep = r.fkine_graph(q, l0, l1).inv() * Tep
272272
e = np.sum(np.abs(np.r_[eTep.t, eTep.rpy() * np.pi/180]))
273273

274-
Q[n:, n:] = (1 / e) * np.eye(6)
274+
Q[n:, n:] = 10 * (1 / e) * np.eye(6)
275275
Aeq = np.c_[r.jacobe(q, l0, l1), np.eye(6)]
276276
beq = v.reshape((6,))
277277
Jm = r.jacobm(q, from_link=l0, to_link=l1).reshape(7,)
@@ -348,9 +348,9 @@ def servo(q0, q1, it):
348348
it_max = 20000
349349

350350
probs = 45
351-
j = 0
351+
j = 20
352352

353-
for i in range(probs):
353+
for i in range(j, probs):
354354
print(problems[i, 0], problems[i, 1])
355355
ret = servo(qs[problems[i, 0]], qs[problems[i, 1]], 500)
356356

examples/counter.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -441,7 +441,7 @@ def plane_int(t0, t1, ob):
441441

442442
def link_calc(link, col, ob, q):
443443
di = 0.3
444-
ds = 0.02
444+
ds = 0.0
445445

446446
ret = p.getClosestPoints(col.co, ob.co, di)
447447

@@ -461,7 +461,7 @@ def link_calc(link, col, ob, q):
461461
dp = nh @ ob.v
462462
l_Ain = np.zeros((1, 13))
463463
l_Ain[0, :n] = nh @ Je
464-
l_bin = (0.5 * (d - ds) / (di - ds)) + dp
464+
l_bin = (1 * (d - ds) / (di - ds)) + dp
465465
else:
466466
l_Ain = None
467467
l_bin = None
@@ -500,7 +500,7 @@ def servo(q0, q1, it):
500500
eTep = r.fkine_graph(q, l0, l1).inv() * Tep
501501
e = np.sum(np.abs(np.r_[eTep.t, eTep.rpy() * np.pi/180]))
502502

503-
Q[n:, n:] = (1 / e) * np.eye(6)
503+
Q[n:, n:] = 10 * (1 / e) * np.eye(6)
504504
Aeq = np.c_[r.jacobe(q, l0, l1), np.eye(6)]
505505
beq = v.reshape((6,))
506506
Jm = r.jacobm(q, from_link=l0, to_link=l1).reshape(7,)

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy