-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathbaseline.py
255 lines (214 loc) · 9.17 KB
/
baseline.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
# Licensing Information: You are free to use or extend these projects for
# educational purposes provided that (1) you do not distribute or publish
# solutions, (2) you retain this notice, and (3) you provide clear
# attribution to UC San Diego.
# Created by Yuzhe Qin, Fanbo Xiang
from final_env import FinalEnv, SolutionBase
import numpy as np
from sapien.core import Pose
from transforms3d.euler import euler2quat, quat2euler
from transforms3d.quaternions import quat2axangle, qmult, qinverse
class Solution(SolutionBase):
"""
This is a very bad baseline solution
It operates in the following ways:
1. roughly align the 2 spades
2. move the spades towards the center
3. lift 1 spade and move the other away
4. somehow transport the lifted spade to the bin
5. pour into the bin
6. go back to 1
"""
def init(self, env: FinalEnv):
self.phase = 0
self.drive = 0
meta = env.get_metadata()
self.box_ids = meta['box_ids']
r1, r2, c1, c2, c3, c4 = env.get_agents()
self.ps = [1000, 800, 600, 600, 200, 200, 100]
self.ds = [1000, 800, 600, 600, 200, 200, 100]
r1.configure_controllers(self.ps, self.ds)
r2.configure_controllers(self.ps, self.ds)
def act(self, env: FinalEnv, current_timestep: int):
r1, r2, c1, c2, c3, c4 = env.get_agents()
pf_left = f = r1.get_compute_functions()['passive_force'](True, True, False)
pf_right = f = r2.get_compute_functions()['passive_force'](True, True, False)
if self.phase == 0:
t1 = [2, 1, 0, -1.5, -1, 1, -2]
t2 = [-2, 1, 0, -1.5, 1, 1, -2]
r1.set_action(t1, [0] * 7, pf_left)
r2.set_action(t2, [0] * 7, pf_right)
if np.allclose(r1.get_observation()[0], t1, 0.05, 0.05) and np.allclose(
r2.get_observation()[0], t2, 0.05, 0.05):
self.phase = 1
self.counter = 0
self.selected_x = None
if self.phase == 1:
self.counter += 1
if (self.counter == 1):
selected = self.pick_box(c4)
self.selected_x = selected[0]
if self.selected_x is None:
return False
target_pose_left = Pose([self.selected_x, 0.5, 0.67], euler2quat(np.pi, -np.pi / 3, -np.pi / 2))
self.diff_drive(r1, 9, target_pose_left)
target_pose_right = Pose([self.selected_x, -0.5, 0.6], euler2quat(np.pi, -np.pi / 3, np.pi / 2))
self.diff_drive(r2, 9, target_pose_right)
if self.counter == 2000 / 5:
self.phase = 2
self.counter = 0
pose = r1.get_observation()[2][9]
p, q = pose.p, pose.q
p[1] = 0.07
self.pose_left = Pose(p, q)
pose = r2.get_observation()[2][9]
p, q = pose.p, pose.q
p[1] = -0.07
self.pose_right = Pose(p, q)
if self.phase == 2:
self.counter += 1
self.diff_drive(r1, 9, self.pose_left)
self.diff_drive(r2, 9, self.pose_right)
if self.counter == 2000 / 5:
self.phase = 3
pose = r2.get_observation()[2][9]
p, q = pose.p, pose.q
p[2] += 0.2
self.pose_right = Pose(p, q)
pose = r1.get_observation()[2][9]
p, q = pose.p, pose.q
p[1] = 0.5
q = euler2quat(np.pi, -np.pi / 2, -np.pi / 2)
self.pose_left = Pose(p, q)
self.counter = 0
if self.phase == 3:
self.counter += 1
self.diff_drive(r1, 9, self.pose_left)
self.diff_drive(r2, 9, self.pose_right)
if self.counter == 200 / 5:
self.phase = 4
self.counter = 0
if self.phase == 4:
self.counter += 1
if (self.counter < 3000 / 5):
pose = r2.get_observation()[2][9]
p, q = pose.p, pose.q
q = euler2quat(np.pi, -np.pi / 1.5, quat2euler(q)[2])
self.diff_drive2(r2, 9, Pose(p, q), [4, 5, 6], [0, 0, 0, -1, 0], [0, 1, 2, 3, 4])
elif (self.counter < 6000 / 5):
pose = r2.get_observation()[2][9]
p, q = pose.p, pose.q
q = euler2quat(np.pi, -np.pi / 1.5, quat2euler(q)[2])
self.diff_drive2(r2, 9, Pose(p, q), [4, 5, 6], [0, 0, 1, -1, 0], [0, 1, 2, 3, 4])
elif (self.counter < 9000 / 5):
p = [-1, 0, 1.5]
q = euler2quat(0, -np.pi / 1.5, 0)
self.diff_drive(r2, 9, Pose(p, q))
else:
self.phase = 0
# return False
def diff_drive(self, robot, index, target_pose):
"""
this diff drive is very hacky
it tries to transport the target pose to match an end pose
by computing the pose difference between current pose and target pose
then it estimates a cartesian velocity for the end effector to follow.
It uses differential IK to compute the required joint velocity, and set
the joint velocity as current step target velocity.
This technique makes the trajectory very unstable but it still works some times.
"""
pf = robot.get_compute_functions()['passive_force'](True, True, False)
max_v = 0.1
max_w = np.pi
qpos, qvel, poses = robot.get_observation()
current_pose: Pose = poses[index]
delta_p = target_pose.p - current_pose.p
delta_q = qmult(target_pose.q, qinverse(current_pose.q))
axis, theta = quat2axangle(delta_q)
if (theta > np.pi):
theta -= np.pi * 2
t1 = np.linalg.norm(delta_p) / max_v
t2 = theta / max_w
t = max(np.abs(t1), np.abs(t2), 0.001)
thres = 0.1
if t < thres:
k = (np.exp(thres) - 1) / thres
t = np.log(k * t + 1)
v = delta_p / t
w = theta / t * axis
target_qvel = robot.get_compute_functions()['cartesian_diff_ik'](np.concatenate((v, w)), 9)
robot.set_action(qpos, target_qvel, pf)
def diff_drive2(self, robot, index, target_pose, js1, joint_target, js2):
"""
This is a hackier version of the diff_drive
It uses specified joints to achieve the target pose of the end effector
while asking some other specified joints to match a global pose
"""
pf = robot.get_compute_functions()['passive_force'](True, True, False)
max_v = 0.1
max_w = np.pi
qpos, qvel, poses = robot.get_observation()
current_pose: Pose = poses[index]
delta_p = target_pose.p - current_pose.p
delta_q = qmult(target_pose.q, qinverse(current_pose.q))
axis, theta = quat2axangle(delta_q)
if (theta > np.pi):
theta -= np.pi * 2
t1 = np.linalg.norm(delta_p) / max_v
t2 = theta / max_w
t = max(np.abs(t1), np.abs(t2), 0.001)
thres = 0.1
if t < thres:
k = (np.exp(thres) - 1) / thres
t = np.log(k * t + 1)
v = delta_p / t
w = theta / t * axis
target_qvel = robot.get_compute_functions()['cartesian_diff_ik'](np.concatenate((v, w)), 9)
for j, target in zip(js2, joint_target):
qpos[j] = target
robot.set_action(qpos, target_qvel, pf)
def get_global_position_from_camera(self, camera, depth, x, y):
"""
camera: an camera agent
depth: the depth obsrevation
x, y: the horizontal, vertical index for a pixel, you would access the images by image[y, x]
"""
cm = camera.get_metadata()
proj, model = cm['projection_matrix'], cm['model_matrix']
w, h = cm['width'], cm['height']
# get 0 to 1 coordinate for (x, y) coordinates
xf, yf = (x + 0.5) / w, 1 - (y + 0.5) / h
# get 0 to 1 depth value at (x,y)
zf = depth[int(y), int(x)]
# get the -1 to 1 (x,y,z) coordinates
ndc = np.array([xf, yf, zf, 1]) * 2 - 1
# transform from image space to view space
v = np.linalg.inv(proj) @ ndc
v /= v[3]
# transform from view space to world space
v = model @ v
return v
def pick_box(self, c):
color, depth, segmentation = c.get_observation()
np.random.shuffle(self.box_ids)
for i in self.box_ids:
m = np.where(segmentation == i)
if len(m[0]):
min_x = 10000
max_x = -1
min_y = 10000
max_y = -1
for y, x in zip(m[0], m[1]):
min_x = min(min_x, x)
max_x = max(max_x, x)
min_y = min(min_y, y)
max_y = max(max_y, y)
x, y = round((min_x + max_x) / 2), round((min_y + max_y) / 2)
return self.get_global_position_from_camera(c, depth, x, y)
return False
if __name__ == '__main__':
np.random.seed(0)
env = FinalEnv()
# env.run(Solution(), render=True, render_interval=5, debug=True)
env.run(Solution(), render=True, render_interval=5)
env.close()