-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcontrol_prior.py
1488 lines (1177 loc) · 64 KB
/
control_prior.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
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
import glob
import math
import matplotlib.pyplot as plt
import matplotlib.animation as animation
import numpy as np
import os
import taichi as ti
ti.init(arch=ti.cpu)
import torch
from configs.config import gen_args
from matplotlib import cm
from models.prior_model_distributed import Prior_Model
from metrics.metric import ChamferLoss, EarthMoverLoss, HausdorffLoss
from plb.engine.taichi_env import TaichiEnv
from plb.config import load
from plb.algorithms import sample_data
from tqdm import tqdm, trange
from transforms3d.quaternions import *
from transforms3d.axangles import axangle2mat
from sys import platform
from utils.robocraft_utils import set_seed, Tee, count_parameters
from utils.robocraft_utils import load_data, get_scene_info, get_env_group, prepare_input
from utils.utils import load_single_model, load_checkpoint
use_gpu = True
device = torch.device("cuda" if torch.cuda.is_available() and use_gpu else "cpu")
from pdb import set_trace
task_params = {
"mid_point": np.array([0.5, 0.14, 0.5, 0, 0, 0]),
"sample_radius": 0.4,
"len_per_grip": 30,
"len_per_grip_back": 10,
"floor_pos": np.array([0.5, 0, 0.5]),
"n_shapes": 3,
"n_shapes_floor": 9,
"n_shapes_per_gripper": 11,
"gripper_mid_pt": int((11 - 1) / 2),
"gripper_gap_limits": np.array([0.14, 0.06]), # ((0.4 * 2 - (0.23)) / (2 * 30), (0.4 * 2 - 0.15) / (2 * 30)),
"p_noise_scale": 0.08,
"p_noise_bound": 0.1,
"loss_weights": [0.9, 0.1, 0.0],
"tool_size": 0.045,
"CEM_opt_iter": 3,
"CEM_init_pose_sample_size": 40,
"CEM_gripper_rate_sample_size": 8,
"GD_batch_size": 1
}
emd_loss = EarthMoverLoss()
chamfer_loss = ChamferLoss()
h_loss = HausdorffLoss()
def visualize_sampled_init_pos(init_pose_seqs, reward_seqs, idx, path):
init_pose_seqs = init_pose_seqs.cpu().numpy()
reward_seqs = reward_seqs.cpu().numpy()
idx = idx.cpu().numpy()
n_subplots = init_pose_seqs.shape[1]
fig, axs = plt.subplots(1, n_subplots)
fig.set_size_inches(8 * n_subplots, 4.8)
for i in range(n_subplots):
if n_subplots == 1:
ax = axs
else:
ax = axs[i]
ax.scatter(init_pose_seqs[:, i, task_params["gripper_mid_pt"], 0],
init_pose_seqs[:, i, task_params["gripper_mid_pt"], 2],
c=reward_seqs, cmap=cm.jet)
ax.set_title(f"GRIP {i+1}")
ax.set_xlabel('x coordinate')
ax.set_ylabel('z coordinate')
color_map = cm.ScalarMappable(cmap=cm.jet)
color_map.set_array(reward_seqs[idx])
plt.colorbar(color_map, ax=axs)
plt.savefig(path)
# plt.show()
def visualize_loss(loss_lists, path):
plt.figure(figsize=[16, 9])
for loss_list in loss_lists:
iters, loss = map(list, zip(*loss_list))
plt.plot(iters, loss, linewidth=6)
plt.xlabel('epochs', fontsize=30)
plt.ylabel('loss', fontsize=30)
plt.title('Test Loss', fontsize=35)
# plt.legend(fontsize=30)
plt.xticks(fontsize=25)
plt.yticks(fontsize=25)
plt.savefig(path)
# plt.show()
def visualize_rollout_loss(loss_lists, path):
plt.figure(figsize=[16, 9])
labels = ["model", "sim"]
for label, loss_list in zip(labels, loss_lists):
iters, loss = map(list, zip(*loss_list))
plt.plot(iters, loss, label=label, linewidth=6)
plt.xlabel('iteration', fontsize=30)
plt.ylabel('loss', fontsize=30)
plt.title('Rollout Loss', fontsize=35)
plt.legend(fontsize=30)
plt.xticks(fontsize=25)
plt.yticks(fontsize=25)
plt.savefig(path)
# plt.show()
def visualize_points(all_points, n_particles, path):
# print(all_points.shape)
points = all_points[:n_particles]
shapes = all_points[n_particles:]
fig = plt.figure()
ax = fig.add_subplot(111, projection='3d')
ax.view_init(45, 135)
ax.scatter(points[:, 0], points[:, 2], points[:, 1], c='b', s=20)
ax.scatter(shapes[:, 0], shapes[:, 2], shapes[:, 1], c='r', s=20)
extents = np.array([getattr(ax, 'get_{}lim'.format(dim))() for dim in 'xyz'])
sz = extents[:, 1] - extents[:, 0]
centers = np.mean(extents, axis=1)
maxsize = max(abs(sz))
r = 0.25 # maxsize / 2
for ctr, dim in zip(centers, 'xyz'):
getattr(ax, 'set_{}lim'.format(dim))(ctr - r, ctr + r)
ax.invert_yaxis()
plt.savefig(path)
# plt.show()
def visualize_points_helper(ax, all_points, n_particles, p_color='b'):
points = ax.scatter(all_points[:n_particles, 0], all_points[:n_particles, 2], all_points[:n_particles, 1], c=p_color, s=10)
shapes = ax.scatter(all_points[n_particles:, 0], all_points[n_particles:, 2], all_points[n_particles:, 1], c='r', s=10)
extents = np.array([getattr(ax, 'get_{}lim'.format(dim))() for dim in 'xyz'])
sz = extents[:, 1] - extents[:, 0]
centers = np.mean(extents, axis=1)
maxsize = max(abs(sz))
r = 0.25 # maxsize / 2
for ctr, dim in zip(centers, 'xyz'):
getattr(ax, 'set_{}lim'.format(dim))(ctr - r, ctr + r)
ax.invert_yaxis()
return points, shapes
def plt_render(particles_set, target_shape, n_particle, render_path):
# particles_set[0] = np.concatenate((particles_set[0][:, :n_particle], particles_set[1][:, n_particle:]), axis=1)
n_frames = particles_set[0].shape[0]
rows = 2
cols = 3
fig, big_axes = plt.subplots(rows, 1, figsize=(3*cols, 3*rows))
row_titles = ['Simulator', 'Model']
views = [(90, 90), (0, 90), (45, 135)]
plot_info_all = {}
for i in range(rows):
big_axes[i].set_title(row_titles[i], fontweight='semibold')
big_axes[i].axis('off')
plot_info = []
for j in range(cols):
ax = fig.add_subplot(rows, cols, i * cols + j + 1, projection='3d')
ax.view_init(*views[j])
visualize_points_helper(ax, target_shape, n_particle, p_color='c')
points, shapes = visualize_points_helper(ax, particles_set[i][0], n_particle)
plot_info.append((points, shapes))
plot_info_all[row_titles[i]] = plot_info
plt.tight_layout()
# plt.show()
def update(step):
outputs = []
for i in range(rows):
states = particles_set[i]
for j in range(cols):
points, shapes = plot_info_all[row_titles[i]][j]
points._offsets3d = (states[step, :n_particle, 0], states[step, :n_particle, 2], states[step, :n_particle, 1])
shapes._offsets3d = (states[step, n_particle:, 0], states[step, n_particle:, 2], states[step, n_particle:, 1])
outputs.append(points)
outputs.append(shapes)
return outputs
anim = animation.FuncAnimation(fig, update, frames=np.arange(0, n_frames), blit=False)
# plt.show()
anim.save(render_path, writer=animation.PillowWriter(fps=20))
def expand(batch_size, info):
length = len(info.shape)
if length == 2:
info = info.expand([batch_size, -1])
elif length == 3:
info = info.expand([batch_size, -1, -1])
elif length == 4:
info = info.expand([batch_size, -1, -1, -1])
return info
def random_rotate(mid_point, z_vec, z_angle):
mid_point = mid_point[:3]
z_mat = axangle2mat(z_vec, z_angle, is_normalized=True)
all_mat = z_mat
quat = torch.tensor(mat2quat(all_mat))
return quat
def get_pose(new_mid_point, rot_noise, z_angle, mode):
# if not torch.is_tensor(new_mid_point):
# new_mid_point = torch.tensor(new_mid_point)
if not torch.is_tensor(rot_noise):
rot_noise = torch.tensor(rot_noise)
x1 = new_mid_point[0] - task_params["sample_radius"] * torch.cos(rot_noise)
y1 = new_mid_point[2] + task_params["sample_radius"] * torch.sin(rot_noise)
x2 = new_mid_point[0] + task_params["sample_radius"] * torch.cos(rot_noise)
y2 = new_mid_point[2] - task_params["sample_radius"] * torch.sin(rot_noise)
unit_quat = torch.tensor([1.0, 0.0, 0.0, 0.0])
gripper1_pos = torch.tensor([x1, new_mid_point[1], y1])
gripper2_pos = torch.tensor([x2, new_mid_point[1], y2])
if mode == '3d':
z_vec = torch.tensor([torch.cos(rot_noise), 0, torch.sin(rot_noise)])
unit_quat = random_rotate(new_mid_point, z_vec, z_angle)
# import pdb; pdb.set_trace()
new_prim1 = []
for j in range(task_params["n_shapes_per_gripper"]):
prim1_pos = torch.stack([x1, torch.tensor(new_mid_point[1].item() + 0.018 * (j-5)), y1])
prim1_tmp = torch.cat((prim1_pos, unit_quat))
new_prim1.append(prim1_tmp)
new_prim1 = torch.stack(new_prim1)
# import pdb; pdb.set_trace()
if mode == '3d':
new_prim1_pos = (torch.tensor(quat2mat(unit_quat)) @ (new_prim1[:, :3] - gripper1_pos).T).T + gripper1_pos
new_prim1 = torch.cat((new_prim1_pos, new_prim1[:, 3:]), 1)
new_prim2 = []
for j in range(task_params["n_shapes_per_gripper"]):
prim2_pos = torch.stack([x2, torch.tensor(new_mid_point[1].item() + 0.018 * (j-5)), y2])
prim2_tmp = torch.cat((prim2_pos, unit_quat))
new_prim2.append(prim2_tmp)
new_prim2 = torch.stack(new_prim2)
if mode == '3d':
new_prim2_pos = (torch.tensor(quat2mat(unit_quat)) @ (new_prim2[:, :3] - gripper2_pos).T).T + gripper2_pos
new_prim2 = torch.cat((new_prim2_pos, new_prim2[:, 3:]), 1)
init_pose = torch.cat((new_prim1, new_prim2), 1)
return init_pose
def get_action_seq(rot_noise, gripper_rate):
if not torch.is_tensor(rot_noise):
rot_noise = torch.tensor(rot_noise)
if not torch.is_tensor(gripper_rate):
gripper_rate = torch.tensor(gripper_rate)
# n_actions = (gripper_rate - torch.remainder(gripper_rate, task_params["gripper_rate"])) / task_params["gripper_rate"]
# n_actions = gripper_rate / task_params["gripper_rate"]
zero_pad = torch.zeros(3)
actions = []
counter = 0
while counter < task_params["len_per_grip"]:
x = gripper_rate * torch.cos(rot_noise)
y = -gripper_rate * torch.sin(rot_noise)
prim1_act = torch.stack([x/0.02, torch.tensor(0), y/0.02])
prim2_act = torch.stack([-x/0.02, torch.tensor(0), -y/0.02])
act = torch.cat((prim1_act, zero_pad, prim2_act, zero_pad))
actions.append(act)
counter += 1
# actions = actions[:task_params["len_per_grip"]]
# for _ in range(task_params["len_per_grip"] - len(actions)):
# actions.append(torch.zeros(12))
counter = 0
while counter < task_params["len_per_grip_back"]:
x = -gripper_rate * torch.cos(rot_noise)
y = gripper_rate * torch.sin(rot_noise)
prim1_act = torch.stack([x/0.02, torch.tensor(0), y/0.02])
prim2_act = torch.stack([-x/0.02, torch.tensor(0), -y/0.02])
act = torch.cat((prim1_act, zero_pad, prim2_act, zero_pad))
actions.append(act)
counter += 1
actions = torch.stack(actions)
# print(f"Sampled actions: {actions}")
return actions
def get_params_from_pose(init_pose_seq):
# init_pose_seq.shape :
# import pdb; pdb.set_trace()
if not torch.is_tensor(init_pose_seq):
init_pose_seq = torch.tensor(init_pose_seq)
mid_point_seq = (init_pose_seq[:, task_params["gripper_mid_pt"], :3] + init_pose_seq[:, task_params["gripper_mid_pt"], 7:10]) / 2
angle_seq = torch.atan2(init_pose_seq[:, task_params["gripper_mid_pt"], 2] - mid_point_seq[:, 2], \
init_pose_seq[:, task_params["gripper_mid_pt"], 0] - mid_point_seq[:, 0])
a = init_pose_seq[:, 0, :3] - init_pose_seq[:, -1, :3]
b = torch.tensor([[0.0, 1.0, 0.0]]).expand(init_pose_seq.shape[0], -1)
z_angle_seq = torch.acos((a * b).sum(dim=1) / (a.pow(2).sum(dim=1).pow(0.5) * b.pow(2).sum(dim=1).pow(0.5)))
pi = torch.full(angle_seq.shape, math.pi)
angle_seq_new = pi - angle_seq
z_angle_seq_new = pi - z_angle_seq
return mid_point_seq, angle_seq_new, z_angle_seq_new
def get_action_seq_from_pose(init_pose_seq, gripper_rates):
# import pdb; pdb.set_trace()
_, rot_noise_seq, _ = get_params_from_pose(init_pose_seq)
act_seq = []
for i in range(len(rot_noise_seq)):
act_seq.append(get_action_seq(rot_noise_seq[i], gripper_rates[i]))
act_seq = torch.stack(act_seq)
return act_seq
def get_gripper_rate_from_action_seq(act_seq):
# act_seq.shape : [n_grip_sample, 40, 12]
gripper_rate_seq = []
for i in range(act_seq.shape[0]):
gripper_rate = torch.linalg.norm(act_seq[i, 0, :3] * 0.02)
gripper_rate_seq.append(gripper_rate)
gripper_rate_seq = torch.stack(gripper_rate_seq)
return gripper_rate_seq
def sample_particles(env, k_fps_particles, n_particles=2000):
prim_pos1 = env.primitives.primitives[0].get_state(0)
prim_pos2 = env.primitives.primitives[1].get_state(0)
prim_pos = [prim_pos1[:3], prim_pos2[:3]]
prim_rot = [prim_pos1[3:], prim_pos2[3:]]
img = env.render_multi(mode='rgb_array', spp=3)
rgb, depth = img[0], img[1]
tool_info = {'tool_size': task_params["tool_size"]}
ext1=env.renderer.get_ext(env.render_cfg.camera_rot_1, np.array(env.render_cfg.camera_pos_1))
ext2=env.renderer.get_ext(env.render_cfg.camera_rot_2, np.array(env.render_cfg.camera_pos_2))
ext3=env.renderer.get_ext(env.render_cfg.camera_rot_3, np.array(env.render_cfg.camera_pos_3))
ext4=env.renderer.get_ext(env.render_cfg.camera_rot_4, np.array(env.render_cfg.camera_pos_4))
intrinsic = env.renderer.get_int()
cam_params = {'cam1_ext': ext1, 'cam2_ext': ext2, 'cam3_ext': ext3, 'cam4_ext': ext4, 'intrinsic': intrinsic}
sampled_points = sample_data.gen_data_one_frame(rgb, depth, cam_params, prim_pos, prim_rot, tool_info, back=False, prev_pcd=[])
positions = sample_data.update_position(task_params["n_shapes"], prim_pos, pts=sampled_points,
floor=task_params["floor_pos"])
shape_positions = sample_data.shape_aug(positions, k_fps_particles)
return shape_positions
def add_shapes(state_seq, init_pose_seq, act_seq, k_fps_particles, mode):
updated_state_seq = []
for i in range(act_seq.shape[0]):
prim_pos1 = init_pose_seq[i, task_params["gripper_mid_pt"], :3].clone()
prim_pos2 = init_pose_seq[i, task_params["gripper_mid_pt"], 7:10].clone()
prim_rot1 = init_pose_seq[i, task_params["gripper_mid_pt"], 3:7].clone()
prim_rot2 = init_pose_seq[i, task_params["gripper_mid_pt"], 10:].clone()
for j in range(act_seq.shape[1]):
idx = i * act_seq.shape[1] + j
prim_pos1 += 0.02 * act_seq[i, j, :3]
prim_pos2 += 0.02 * act_seq[i, j, 6:9]
positions = sample_data.update_position(task_params["n_shapes"], [prim_pos1, prim_pos2], pts=state_seq[idx],
floor=task_params["floor_pos"])
if mode == '2d':
shape_positions = sample_data.shape_aug(positions, k_fps_particles)
else:
shape_positions = sample_data.shape_aug_3D(positions, prim_rot1, prim_rot2, k_fps_particles)
updated_state_seq.append(shape_positions)
return np.stack(updated_state_seq)
class Planner(object):
def __init__(self, args, taichi_env, env_init_state, scene_params, n_particle, n_shape, prior_model, all_p,
goal_shapes, task_params, use_gpu, rollout_path, env="gripper"):
self.args = args
self.batch_size = args.shooting_batch_size
self.sample_size = args.shooting_batch_size
self.taichi_env = taichi_env
self.env_init_state = env_init_state
self.scene_params = scene_params
self.n_particle = n_particle
self.n_shape = n_shape
self.prior_model = prior_model
self.all_p = all_p
self.goal_shapes = goal_shapes
self.task_params = task_params
self.use_gpu = use_gpu
self.rollout_path = rollout_path
self.env = env
self.grip_cur = ''
self.CEM_opt_iter_cur = 0
if args.debug:
self.batch_size = 1
self.sample_size = 4
task_params["CEM_init_pose_sample_size"] = 4
task_params["CEM_gripper_rate_sample_size"] = 4
def trajectory_optimization(self):
state_goal_final = self.get_state_goal(self.args.n_grips - 1)
visualize_points(state_goal_final[-1], self.n_particle, os.path.join(self.rollout_path, f'goal_particles'))
# set_trace()
if self.args.control_algo == 'fix':
best_init_pose_seq, best_act_seq, best_model_loss = self.trajectory_optimization_with_horizon(self.args.n_grips, self.args.correction)
best_sim_loss = self.visualize_results(best_init_pose_seq, best_act_seq, state_goal_final, self.args.n_grips)
elif self.args.control_algo == 'search':
model_loss_list = []
sim_loss_list = []
for grip_num in range(self.args.n_grips, 0, -1):
init_pose_seq, act_seq, loss_seq = self.trajectory_optimization_with_horizon(
grip_num, self.args.correction)
with open(f"{self.rollout_path}/init_pose_seq_{grip_num}.npy", 'wb') as f:
np.save(f, init_pose_seq)
with open(f"{self.rollout_path}/act_seq_{grip_num}.npy", 'wb') as f:
np.save(f, act_seq)
loss_sim = self.visualize_results(init_pose_seq, act_seq, state_goal_final, grip_num)
model_loss_list.append([grip_num, loss_seq.item()])
sim_loss_list.append([grip_num, loss_sim.item()])
print(f"=============== With {grip_num} grips -> model_loss: {loss_seq}; sim_loss: {loss_sim} ===============")
if grip_num == self.args.n_grips:
best_init_pose_seq = init_pose_seq
best_act_seq = act_seq
best_model_loss = loss_seq
best_sim_loss = loss_sim
best_idx = grip_num
else:
if loss_sim < best_sim_loss:
best_init_pose_seq = init_pose_seq
best_act_seq = act_seq
best_model_loss = loss_seq
best_sim_loss = loss_sim
best_idx = grip_num
visualize_rollout_loss([model_loss_list, sim_loss_list], os.path.join(self.rollout_path, f'rollout_loss'))
os.system(f"cp {os.path.join(self.rollout_path, f'anim_{best_idx}.gif')} {os.path.join(self.rollout_path, f'best_anim.gif')}")
os.system(f"cp {os.path.join(self.rollout_path, f'init_pose_seq_{best_idx}.npy')} {os.path.join(self.rollout_path, f'init_pose_seq_opt.npy')}")
os.system(f"cp {os.path.join(self.rollout_path, f'act_seq_{best_idx}.npy')} {os.path.join(self.rollout_path, f'act_seq_opt.npy')}")
elif self.args.control_algo == 'predict':
checkpoint = None
model_loss_list = []
sim_loss_list = []
n_iters = self.args.n_grips - self.args.predict_horizon + 1
for i in range(n_iters):
init_pose_seq, act_seq, loss_seq = self.trajectory_optimization_with_horizon(
self.args.predict_horizon, i==n_iters-1, checkpoint=checkpoint)
# set_trace()
checkpoint = [init_pose_seq[:1-self.args.predict_horizon], act_seq[:1-self.args.predict_horizon]]
with open(f"{self.rollout_path}/init_pose_seq_{i}.npy", 'wb') as f:
np.save(f, init_pose_seq)
with open(f"{self.rollout_path}/act_seq_{i}.npy", 'wb') as f:
np.save(f, act_seq)
loss_sim = self.visualize_results(init_pose_seq, act_seq, state_goal_final, i)
model_loss_list.append([i, loss_seq.item()])
sim_loss_list.append([i, loss_sim.item()])
print(f"=============== Iteration {i} -> model_loss: {loss_seq}; sim_loss: {loss_sim} ===============")
if i == 0:
best_init_pose_seq = init_pose_seq
best_act_seq = act_seq
best_model_loss = loss_seq
best_sim_loss = loss_sim
best_idx = i
else:
if loss_sim < best_sim_loss:
best_init_pose_seq = init_pose_seq
best_act_seq = act_seq
best_model_loss = loss_seq
best_sim_loss = loss_sim
best_idx = i
visualize_rollout_loss([model_loss_list, sim_loss_list], os.path.join(self.rollout_path, f'rollout_loss'))
os.system(f"cp {os.path.join(self.rollout_path, f'anim_{best_idx}.gif')} {os.path.join(self.rollout_path, f'best_anim.gif')}")
os.system(f"cp {os.path.join(self.rollout_path, f'init_pose_seq_{best_idx}.npy')} {os.path.join(self.rollout_path, f'init_pose_seq_opt.npy')}")
os.system(f"cp {os.path.join(self.rollout_path, f'act_seq_{best_idx}.npy')} {os.path.join(self.rollout_path, f'act_seq_opt.npy')}")
return best_init_pose_seq.cpu(), best_act_seq.cpu(), best_model_loss.cpu(), best_sim_loss.cpu()
def trajectory_optimization_with_horizon(self, grip_num, correction, checkpoint=None):
if checkpoint:
init_pose_seq, act_seq = checkpoint
else:
init_pose_seq = torch.Tensor()
act_seq = torch.Tensor()
# set_trace()
# when first iteration, init_pose_seq is [0]
# when second iteration, init_pose_seq is [1, 11, 14]
for i in range(grip_num): #
# set_trace()
self.grip_cur = f'{grip_num}-{i+1}'
print(f'=============== {i+1}/{grip_num} ===============')
if self.args.subgoal:
state_goal = self.get_state_goal(i)
n_grips_sample = 1
else:
state_goal = self.get_state_goal(self.args.n_grips - 1)
n_grips_sample = grip_num - i
# set_trace()
init_pose_seqs_pool, act_seqs_pool = self.sample_action_params(n_grips_sample) # sample action params
# set_trace()
# init_pose_seqs_pool.shape : [4, n_grips_sample, 11, 14]
# 4 : sample_size, 11 : primitive_size, 14 : primitive_1.xyz + [1,0,0,0] + primitive_2.xyz + [1,0,0,0]
# act_seqs_pool.shape : [4, n_grips_sample, 40, 12]
# 4 : sample_size, 40 : len_per_grip + len_per_grip_back, 12 : [act1 + [0,0,0] + act2 + [0,0,0]]
# set_trace()
if init_pose_seq.numel() == 0:
init_pose_seq_cur = init_pose_seqs_pool[0]
act_seq_cur = act_seqs_pool[0, 0, 0].unsqueeze(0).unsqueeze(0)
else:
init_pose_seq_cur = init_pose_seq
act_seq_cur = act_seq
# import pdb; pdb.set_trace()
# init_pose_seq_cur.shape : [n_grips_sample, 11 ,14]
# act_seq_cur.shape : [1, 1, 12]
# set_trace()
state_cur_sim = self.sim_rollout(init_pose_seq_cur.unsqueeze(0), act_seq_cur.unsqueeze(0))[0].squeeze() # sim_rollout in simulator
# set_trace()
# state_cur_sim.shape.shape : [4, 331, 3]
# 4 : sample_size, 331 : all_states, 3 : xyz positions
state_cur_sim_particles = state_cur_sim[:, :self.n_particle].clone()
self.floor_state = state_cur_sim[:, self.n_particle: self.n_particle + task_params["n_shapes_floor"]].clone()
visualize_points(state_cur_sim[-1], self.n_particle, os.path.join(self.rollout_path, f'sim_particles_{self.grip_cur}'))
# visualize_points(state_cur_gt[-1], self.n_particle, os.path.join(self.rollout_path, f'gt_particles_{i}'))
if checkpoint == None and i == 0:
self.initial_state = state_cur_sim_particles
if i == 0 or self.args.correction:
state_cur = state_cur_sim_particles
else:
state_cur = state_seq_opt[-self.args.n_his:].clone()
print(f"state_cur: {state_cur.shape}, state_goal: {state_goal.shape}")
# set_trace()
reward_seqs, model_state_seqs = self.rollout(init_pose_seqs_pool, act_seqs_pool, state_cur, state_goal)
# state_cur.shape [4, 300, 3]
# state_goal.shape [1, 300, 3]
# set_trace()
# reward_seqs.shape : [self.sample_size]
# model_state_seqs.shape : [self.sample_size, self.n_grip_sample * (self.len_per_grip + self.len_per_grip_back), n_particle, 3]
print('sampling: max: %.4f, mean: %.4f, std: %.4f' % (torch.max(reward_seqs), torch.mean(reward_seqs), torch.std(reward_seqs)))
if self.args.opt_algo == 'max':
init_pose_seq_opt, act_seq_opt, loss_opt, state_seq_opt = self.optimize_action_max(
init_pose_seqs_pool, act_seqs_pool, reward_seqs, model_state_seqs)
elif self.args.opt_algo == 'CEM':
for j in range(task_params["CEM_opt_iter"]):
self.CEM_opt_iter_cur = j
if j == task_params["CEM_opt_iter"] - 1:
init_pose_seq_opt, act_seq_opt, loss_opt, state_seq_opt = self.optimize_action_max(
init_pose_seqs_pool, act_seqs_pool, reward_seqs, model_state_seqs)
else:
init_pose_seqs_pool, act_seqs_pool = self.optimize_action_CEM(init_pose_seqs_pool, act_seqs_pool, reward_seqs)
reward_seqs, model_state_seqs = self.rollout(init_pose_seqs_pool, act_seqs_pool, state_cur, state_goal)
elif self.args.opt_algo == "GD":
with torch.set_grad_enabled(True):
init_pose_seq_opt, act_seq_opt, loss_opt, state_seq_opt = self.optimize_action_GD(
init_pose_seqs_pool, act_seqs_pool, reward_seqs, state_cur, state_goal)
# set_trace()
elif self.args.opt_algo == "CEM_GD":
for j in range(task_params["CEM_opt_iter"]):
self.CEM_opt_iter_cur = j
if j == task_params["CEM_opt_iter"] - 1:
with torch.set_grad_enabled(True):
init_pose_seq_opt, act_seq_opt, loss_opt, state_seq_opt = self.optimize_action_GD(init_pose_seqs_pool, act_seqs_pool, reward_seqs, state_cur, state_goal)
else:
init_pose_seqs_pool, act_seqs_pool = self.optimize_action_CEM(init_pose_seqs_pool, act_seqs_pool, reward_seqs)
reward_seqs, model_state_seqs = self.rollout(init_pose_seqs_pool, act_seqs_pool, state_cur, state_goal)
else:
raise NotImplementedError
# pdb.set_trace()
if not self.args.subgoal and correction:
init_pose_seq_opt = init_pose_seq_opt[0].unsqueeze(0)
act_seq_opt = act_seq_opt[0].unsqueeze(0)
init_pose_seq = torch.cat((init_pose_seq, init_pose_seq_opt.clone()))
act_seq = torch.cat((act_seq, act_seq_opt.clone()))
loss_seq = loss_opt.clone()
if not correction:
break
return init_pose_seq, act_seq, loss_seq
def visualize_results(self, init_pose_seq, act_seq, state_goal, i):
model_state_seq = self.model_rollout(self.initial_state, init_pose_seq.unsqueeze(0), act_seq.unsqueeze(0))
sample_state_seq, sim_state_seq = self.sim_rollout(init_pose_seq.unsqueeze(0), act_seq.unsqueeze(0))
mode = '3d' if '3d' in self.args.data_type else '2d'
model_state_seq = add_shapes(model_state_seq[0], init_pose_seq, act_seq, self.n_particle, mode=mode)
sim_state_seq = add_shapes(sim_state_seq[0], init_pose_seq, act_seq, self.n_particle, mode=mode)
sample_state_seq = sample_state_seq.squeeze()
visualize_points(sample_state_seq[-1], self.n_particle, os.path.join(self.rollout_path, f'sim_particles_final_{i}'))
plt_render([sim_state_seq, model_state_seq], state_goal[0], self.n_particle, os.path.join(self.rollout_path, f'anim_{i}.gif'))
loss_sim = torch.neg(self.evaluate_traj(sample_state_seq[:, :self.n_particle].unsqueeze(0), state_goal, self.args.reward_type))
emd_loss = torch.neg(self.evaluate_traj(sample_state_seq[:, :self.n_particle].unsqueeze(0), state_goal, 'emd'))
chamfer_loss = torch.neg(self.evaluate_traj(sample_state_seq[:, :self.n_particle].unsqueeze(0), state_goal, 'chamfer'))
print(f"EMD: {emd_loss}\nChamfer: {chamfer_loss}")
return loss_sim
def get_state_goal(self, i):
goal_idx = min((i + 1) * (task_params["len_per_grip"] + task_params["len_per_grip_back"]) - 1, len(self.all_p) - 1)
state_goal = torch.FloatTensor(self.all_p[goal_idx]).unsqueeze(0)[:, :self.n_particle, :]
if len(self.args.goal_shape_name) > 0 and self.args.goal_shape_name != 'none' and self.args.goal_shape_name[:3] != 'vid':
state_goal = self.goal_shapes[i]
return state_goal
def sample_action_params(self, n_grips):
# np.random.seed(0)
init_pose_seqs = []
act_seqs = []
n_sampled = 0
# self.sample_size is 4
# equal to sample for four times
while n_sampled < self.sample_size:
init_pose_seq = []
act_seq = []
for i in range(n_grips):
p_noise_x = task_params["p_noise_scale"] * (np.random.rand() * 2 - 1)
p_noise_z = task_params["p_noise_scale"] * (np.random.rand() * 2 - 1)
p_noise = np.clip(np.array([p_noise_x, 0, p_noise_z]), a_min=-0.1, a_max=0.1)
new_mid_point = task_params["mid_point"][:3] + p_noise
rot_noise = np.random.uniform(0, np.pi)
z_angle = np.random.uniform(0, np.pi)
#
print(new_mid_point, rot_noise, z_angle)
mode = '3d' if '3d' in self.args.data_type else '2d'
init_pose = get_pose(new_mid_point, rot_noise, z_angle, mode=mode)
# set_trace()
# print(init_pose.shape)
init_pose_seq.append(init_pose)
gripper_rate = np.random.uniform(*task_params["gripper_rate_limits"])
actions = get_action_seq(rot_noise, gripper_rate)
# [40, 12] is the action of the primitives in Taichi Env, 30 to move forward, 10 to backward
# set_trace()
# print(actions.shape)
act_seq.append(actions)
init_pose_seq = torch.stack(init_pose_seq)
init_pose_seqs.append(init_pose_seq)
act_seq = torch.stack(act_seq)
act_seqs.append(act_seq)
n_sampled += 1
# set_trace()
return torch.stack(init_pose_seqs), torch.stack(act_seqs)
def rollout(self, init_pose_seqs_pool, act_seqs_pool, state_cur, state_goal):
# import pdb; pdb.set_trace()
# init_pose_seqs_pool.shape : [self.sample_size, n_grips_sample, 11, 14]
# act_seqs_pool.shape : [self.sample_size, n_grips_sample, len_per_grip_back + len_per_grip, 12]
# state_cur.shape : [self.sample_size, n_particle, 3]
# state_goal.shape : [1, n_particle, 3]
reward_seqs_rollout = []
state_seqs_rollout = []
n_batch = int(math.ceil(init_pose_seqs_pool.shape[0] / self.batch_size))
batches = tqdm(range(n_batch), total=n_batch) if n_batch > 4 else range(n_batch)
for i, _ in enumerate(batches):
# print(f"Batch: {i}/{n_batch}")
# during debug mode, self.batch_size is 1
init_pose_seqs = init_pose_seqs_pool[i*self.batch_size:(i+1)*self.batch_size]
act_seqs = act_seqs_pool[i*self.batch_size:(i+1)*self.batch_size]
# init_pose_seqs.shape : [1, n_grips_sample, 11, 14]
# act_seqs.shpae : [1, n_grips_sample, len_per_grip + len_per_grip_back, 12]
# state_cur.shape : [self.args.n_his, n_particle, 3]
if self.args.use_sim:
state_seqs, = self.sim_rollout(init_pose_seqs, act_seqs)
else:
state_seqs = self.model_rollout(state_cur, init_pose_seqs, act_seqs)
reward_seqs = self.evaluate_traj(state_seqs, state_goal, self.args.reward_type)
# print(f"reward seqs: {reward_seqs}")
# reward_seqs = reward_seqs.data.cpu().numpy()
reward_seqs_rollout.append(reward_seqs)
state_seqs_rollout.append(state_seqs)
# import pdb; pdb.set_trace()
reward_seqs_rollout = torch.cat(reward_seqs_rollout, 0)
state_seqs_rollout = torch.cat(state_seqs_rollout, 0)
return reward_seqs_rollout, state_seqs_rollout
def sim_rollout(self, init_pose_seqs, act_seqs):
# init_pose_seqs.shape : []
# act_seqs.shape : []
sample_state_seq_batch = []
state_seq_batch = []
for t in range(act_seqs.shape[0]):
self.taichi_env.set_state(**self.env_init_state)
state_seq = []
for i in range(act_seqs.shape[1]):
self.taichi_env.primitives.primitives[0].set_state(0, init_pose_seqs[t, i, task_params["gripper_mid_pt"], :7])
self.taichi_env.primitives.primitives[1].set_state(0, init_pose_seqs[t, i, task_params["gripper_mid_pt"], 7:])
for j in range(act_seqs.shape[2]):
self.taichi_env.step(act_seqs[t][i][j])
x = self.taichi_env.simulator.get_x(0)
step_size = len(x) // self.n_particle
# print(f"x before: {x.shape}")
x = x[::step_size]
particles = x[:self.n_particle]
# print(f"x after: {x.shape}")
state_seq.append(particles)
# set_trace()
sample_state = sample_particles(self.taichi_env, self.n_particle)
# sample_state : [331, 3]
state_seq_sample = []
for i in range(self.args.n_his):
state_seq_sample.append(sample_state)
sample_state_seq_batch.append(np.stack(state_seq_sample))
state_seq_batch.append(np.stack(state_seq))
sample_state_seq_batch = torch.from_numpy(np.stack(sample_state_seq_batch))
state_seq_batch = torch.from_numpy(np.stack(state_seq_batch))
# print(f"sample_state_seq_batch: {sample_state_seq_batch.shape}")
return sample_state_seq_batch, state_seq_batch
def model_rollout(
self,
state_cur, # [n_his, n_particle, state_dim]
init_pose_seqs,
act_seqs,
):
if not torch.is_tensor(init_pose_seqs):
init_pose_seqs = torch.tensor(init_pose_seqs)
if not torch.is_tensor(act_seqs):
act_seqs = torch.tensor(act_seqs)
init_pose_seqs = init_pose_seqs.float().to(device)
act_seqs = act_seqs.float().to(device)
state_cur = expand(init_pose_seqs.shape[0], state_cur.float().unsqueeze(0)).to(device)
floor_state = expand(init_pose_seqs.shape[0], self.floor_state.float().unsqueeze(0)).to(device)
memory_init = self.prior_model.init_memory(init_pose_seqs.shape[0], self.n_particle + self.n_shape)
scene_params = self.scene_params.expand(init_pose_seqs.shape[0], -1)
group_gt = get_env_group(self.args, self.n_particle, scene_params, use_gpu=self.use_gpu)
# pdb.set_trace()
states_pred_list = []
# act_seq n_sample, n_grip, grip_len, action_dim
for i in range(act_seqs.shape[1]):
# pdb.set_trace()
shape1 = init_pose_seqs[:, i, :, :3]
shape2 = init_pose_seqs[:, i, :, 7:10]
state_cur = torch.cat([state_cur[:, :, :self.n_particle, :], floor_state, shape1.unsqueeze(1).expand([-1, self.args.n_his, -1, -1]),
shape2.unsqueeze(1).expand([-1, self.args.n_his, -1, -1])], dim=2)
for j in range(act_seqs.shape[2]):
attrs = []
Rr_curs = []
Rs_curs = []
Rn_curs = []
max_n_rel = 0
for k in range(act_seqs.shape[0]):
# pdb.set_trace()
state_last = state_cur[k][-1]
attr, _, Rr_cur, Rs_cur, Rn_cur, cluster_onehot = prepare_input(state_last.detach().cpu().numpy(), self.n_particle,
self.n_shape, self.args, stdreg=self.args.stdreg)
attr = attr.to(device)
Rr_cur = Rr_cur.to(device)
Rs_cur = Rs_cur.to(device)
Rn_cur = Rn_cur.to(device)
max_n_rel = max(max_n_rel, Rr_cur.size(0))
attr = attr.unsqueeze(0)
Rr_cur = Rr_cur.unsqueeze(0)
Rs_cur = Rs_cur.unsqueeze(0)
Rn_cur = Rn_cur.unsqueeze(0)
attrs.append(attr)
Rr_curs.append(Rr_cur)
Rs_curs.append(Rs_cur)
Rn_curs.append(Rn_cur)
attrs = torch.cat(attrs, dim=0)
for k in range(len(Rr_curs)):
Rr, Rs, Rn = Rr_curs[k], Rs_curs[k], Rn_curs[k]
Rr = torch.cat([Rr, torch.zeros((1, max_n_rel - Rr.size(1), self.n_particle + self.n_shape)).to(device)], 1)
Rs = torch.cat([Rs, torch.zeros((1, max_n_rel - Rs.size(1), self.n_particle + self.n_shape)).to(device)], 1)
Rn = torch.cat([Rn, torch.zeros((1, max_n_rel - Rn.size(1), self.n_particle + self.n_shape)).to(device)], 1)
Rr_curs[k], Rs_curs[k], Rn_curs[k] = Rr, Rs, Rn
Rr_curs = torch.cat(Rr_curs, dim=0)
Rs_curs = torch.cat(Rs_curs, dim=0)
Rn_curs = torch.cat(Rn_curs, dim=0)
inputs = [attrs, state_cur, Rr_curs, Rs_curs, Rn_curs, memory_init, group_gt, None]
# pdb.set_trace()
pred_pos, pred_motion_norm, std_cluster = self.prior_model(inputs)
shape1 += act_seqs[:, i, j, :3].unsqueeze(1).expand(-1, task_params["n_shapes_per_gripper"], -1) * 0.02
shape2 += act_seqs[:, i, j, 6:9].unsqueeze(1).expand(-1, task_params["n_shapes_per_gripper"], -1) * 0.02
pred_pos = torch.cat([pred_pos, state_cur[:, -1, self.n_particle: self.n_particle + task_params["n_shapes_floor"], :], shape1, shape2], 1)
# print(f"pred_pos shape: {pred_pos.shape}")
state_cur = torch.cat([state_cur[:, 1:], pred_pos.unsqueeze(1)], 1)
# print(f"state_cur shape: {state_cur.shape}")
# print(torch.cuda.memory_summary())
states_pred_list.append(pred_pos[:, :self.n_particle, :])
states_pred_array = torch.stack(states_pred_list, dim=1).cpu()
# print(f"torch mem allocated: {torch.cuda.memory_allocated()}; torch mem reserved: {torch.cuda.memory_reserved()}")
return states_pred_array
def evaluate_traj(
self,
state_seqs, # [n_sample, n_look_ahead, state_dim]
state_goal, # [state_dim]
reward_type
):
# print(state_seqs.shape, state_goal.shape)
reward_seqs = []
for i in range(state_seqs.shape[0]):
state_final = state_seqs[i, -1].unsqueeze(0)
if state_final.shape != state_goal.shape:
print("Data shape doesn't match in evaluate_traj!")
raise ValueError
# smaller loss, larger reward
if reward_type == "emd":
loss = emd_loss(state_final, state_goal)
elif reward_type == "chamfer":
loss = chamfer_loss(state_final, state_goal)
elif reward_type == "emd_chamfer_h":
emd_weight, chamfer_weight, h_weight = task_params["loss_weights"]
loss = 0
if emd_weight > 0:
loss += emd_weight * emd_loss(state_final, state_goal)
if chamfer_weight > 0:
loss += chamfer_weight * chamfer_loss(state_final, state_goal)
if h_weight > 0:
loss += h_weight * h_loss(state_final, state_goal)
else:
raise NotImplementedError
reward_seqs.append(0.0 - loss)
reward_seqs = torch.stack(reward_seqs)
return reward_seqs
def optimize_action_max(
self,
init_pose_seqs,
act_seqs, # [n_sample, -1, action_dim]
reward_seqs, # [n_sample]
state_seqs
):
idx = torch.argsort(reward_seqs)
loss_opt = torch.neg(reward_seqs[idx[-1]]).view(1)
print(f"Selected idx: {idx[-1]} with reward {reward_seqs[idx[-1]]}")
visualize_sampled_init_pos(init_pose_seqs, reward_seqs, idx, \
os.path.join(self.rollout_path, f'plot_max_{self.grip_cur}'))
# pdb.set_trace()
return init_pose_seqs[idx[-1]], act_seqs[idx[-1]], loss_opt, state_seqs[idx[-1]]
def optimize_action_CEM( # Cross Entropy Method (CEM)
self,
init_pose_seqs,
act_seqs,
reward_seqs, # [n_sample]
best_k_ratio=0.1
):
best_k = max(4, int(init_pose_seqs.shape[0] * best_k_ratio))
idx = torch.argsort(reward_seqs)
print(f"Selected top reward seqs: {reward_seqs[idx[-best_k:]]}")
# print(f"Selected top init pose seqs: {init_pose_seqs[idx[-best_k:], :, task_params["gripper_mid_pt"], :7]}")
visualize_sampled_init_pos(init_pose_seqs, reward_seqs, idx, \
os.path.join(self.rollout_path, f'plot_cem_s{self.grip_cur}_o{self.CEM_opt_iter_cur}'))
# pdb.set_trace()
init_pose_seqs_pool = []
act_seqs_pool = []
for i in range(best_k, 0, -1):
init_pose_seq = init_pose_seqs[idx[-i]]
mid_point_seq, angle_seq, z_angle_seq = get_params_from_pose(init_pose_seq)
act_seq = act_seqs[idx[-i]]
# gripper_rate_seq = get_gripper_rate_from_action_seq(act_seq)
# print(f"Selected init pose seq: {init_pose_seq[:, task_params["gripper_mid_pt"], :7]}")
init_pose_seqs_pool.append(init_pose_seq)
act_seqs_pool.append(act_seq)
for k in range(task_params["CEM_gripper_rate_sample_size"] - 1):
# gripper_rate_noise = torch.clamp(torch.tensor(np.random.randn(init_pose_seq.shape[0])*0.02), max=0.05, min=-0.05)
# gripper_rate_sample = gripper_rate_seq + gripper_rate_noise
gripper_rate_sample = []
for s in range(init_pose_seq.shape[0]):
gripper_rate_sample.append(np.random.uniform(*task_params["gripper_rate_limits"]))
gripper_rate_sample = torch.tensor(gripper_rate_sample)
# print(f"{i} gripper_rate_sample: {gripper_rate_sample}")