From 74c9bdcc2691cd6c25bb2753fa386d2a6f2b7ea9 Mon Sep 17 00:00:00 2001 From: jhavl Date: Mon, 8 Feb 2021 20:32:41 +1000 Subject: [PATCH] Fixed examples for v0.8.0 --- examples/baur.py | 2 +- examples/neo.py | 4 ++-- examples/park.py | 2 +- examples/swift_recording.py | 2 +- examples/vellipse.py | 4 ++-- roboticstoolbox/robot/ERobot.py | 2 +- 6 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/baur.py b/examples/baur.py index 686c38e88..da745ce43 100644 --- a/examples/baur.py +++ b/examples/baur.py @@ -89,4 +89,4 @@ panda.qd[:n] = qd[:n] # Step the simulator by 50 ms - env.step(50) + env.step(0.05) diff --git a/examples/neo.py b/examples/neo.py index 5ec3e7a4a..60fc0693d 100644 --- a/examples/neo.py +++ b/examples/neo.py @@ -108,8 +108,8 @@ # object on the robot to the collision in the scene c_Ain, c_bin = panda.link_collision_damper( collision, panda.q[:n], 0.3, 0.05, 1.0, - startlink=panda.link_dict['panda_link1'], - endlink=panda.link_dict['panda_hand']) + start=panda.link_dict['panda_link1'], + end=panda.link_dict['panda_hand']) # If there are any parts of the robot within the influence distance # to the collision in the scene diff --git a/examples/park.py b/examples/park.py index e9f2e4342..b4913c6f6 100644 --- a/examples/park.py +++ b/examples/park.py @@ -67,4 +67,4 @@ panda.qd[:n] = qd[:n] # Step the simulator by 50 ms - env.step(50) + env.step(0.05) diff --git a/examples/swift_recording.py b/examples/swift_recording.py index 59e5fa354..7996923b6 100644 --- a/examples/swift_recording.py +++ b/examples/swift_recording.py @@ -57,7 +57,7 @@ while not arrived: # The pose of the Panda's end-effector - Te = panda.fkine() + Te = panda.fkine(panda.q) # Transform from the end-effector to desired pose eTep = Te.inv() * Tep diff --git a/examples/vellipse.py b/examples/vellipse.py index 15e51ac62..1ab35809f 100644 --- a/examples/vellipse.py +++ b/examples/vellipse.py @@ -30,8 +30,8 @@ while not arrived: start = time.time() - v, arrived = rp.p_servo(panda.fkine(), Tep, 0.5) - panda.qd = np.linalg.pinv(panda.jacobe()) @ v + v, arrived = rp.p_servo(panda.fkine(panda.q), Tep, 0.5) + panda.qd = np.linalg.pinv(panda.jacobe(panda.q)) @ v env.step(50) stop = time.time() diff --git a/roboticstoolbox/robot/ERobot.py b/roboticstoolbox/robot/ERobot.py index cf9af7b09..d896031b7 100644 --- a/roboticstoolbox/robot/ERobot.py +++ b/roboticstoolbox/robot/ERobot.py @@ -1847,7 +1847,7 @@ def indiv_calculation(link, link_col, q): Je = self.jacobe( q, start=self.base_link, end=link, - offset=link_col.base) + tool=link_col.base) n_dim = Je.shape[1] dp = norm_h @ shape.v l_Ain = np.zeros((1, n))