8000 update neo example · olamarre/robotics-toolbox-python@a723b2e · GitHub
[go: up one dir, main page]

Skip to content

Commit a723b2e

Browse files
committed
update neo example
1 parent f5d53d9 commit a723b2e

File tree

1 file changed

+14
-19
lines changed
  • roboticstoolbox/examples

1 file changed

+14
-19
lines changed

roboticstoolbox/examples/neo.py

Lines changed: 14 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -25,25 +25,16 @@
2525
n = 7
2626

2727
# Make two obstacles with velocities
28-
s0 = sg.Sphere(
29-
radius=0.05,
30-
base=sm.SE3(0.52, 0.4, 0.3)
31-
)
28+
s0 = sg.Sphere(radius=0.05, base=sm.SE3(0.52, 0.4, 0.3))
3229
s0.v = [0, -0.2, 0, 0, 0, 0]
3330

34-
s1 = sg.Sphere(
35-
radius=0.05,
36-
base=sm.SE3(0.1, 0.35, 0.65)
37-
)
31+
s1 = sg.Sphere(radius=0.05, base=sm.SE3(0.1, 0.35, 0.65))
3832
s1.v = [0, -0.2, 0, 0, 0, 0]
3933

4034
collisions = [s0, s1]
4135

4236
# Make a target
43-
target = sg.Sphere(
44-
radius=0.02,
45-
base=sm.SE3(0.6, -0.2, 0.0)
46-
)
37+
target = sg.Sphere(radius=0.02, base=sm.SE3(0.6, -0.2, 0.0))
4738

4839
# Add the Panda and shapes to the simulator
4940
env.add(panda)
@@ -54,7 +45,7 @@
5445
# Set the desired end-effector pose to the location of target
5546
Tep = panda.fkine(panda.q)
5647
Tep.A[:3, 3] = target.base.t
57-
Tep.A[2, 3] += 0.1
48+
# Tep.A[2, 3] += 0.1
5849

5950

6051
def step():
@@ -69,7 +60,7 @@ def step():
6960

7061
# Calulate the required end-effector spatial velocity for the robot
7162
# to approach the goal. Gain is set to 1.0
72-
v, arrived = rtb.p_servo(Te, Tep, 0.5, 0.05)
63+
v, arrived = rtb.p_servo(Te, Tep, 0.5, 0.01)
7364

7465
# Gain term (lambda) for control minimisation
7566
Y = 0.01
@@ -108,9 +99,14 @@ def step():
10899
# Form the velocity damper inequality contraint for each collision
109100
# object on the robot to the collision in the scene
110101
c_Ain, c_bin = panda.link_collision_damper(
111-
collision, panda.q[:n], 0.3, 0.05, 1.0,
112-
start=panda.link_dict['panda_link1'],
113-
end=panda.link_dict['panda_hand'])
102+
collision,
103+
panda.q[:n],
104+
0.3,
105+
0.05,
106+
1.0,
107+
start=panda.link_dict["panda_link1"],
108+
end=panda.link_dict["panda_hand"],
109+
)
114110

115111
# If there are any parts of the robot within the influence distance
116112
# to the collision in the scene
@@ -147,5 +143,4 @@ def run():
147143

148144

149145
step()
150-
151-
cProfile.run('run()')
146+
run()

0 commit comments

Comments
 (0)
0