forked from ttblue/tps_normals
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathtn_do_task_eval.py
executable file
·1402 lines (1152 loc) · 75.9 KB
/
tn_do_task_eval.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
#!/usr/bin/env python
from __future__ import division
import pprint
import argparse
import eval_util, sim_util, util
from rapprentice import tps_registration, planning
from rapprentice import registration, colorize, berkeley_pr2, \
animate_traj, ros2rave, plotting_openrave, task_execution, \
tps, func_utils, resampling, ropesim, rope_initialization, clouds
from rapprentice import math_utils as mu
from rapprentice.yes_or_no import yes_or_no
import pdb, time
import trajoptpy, openravepy
from rope_qlearn import get_closing_pts, get_closing_inds
from knot_classifier import isKnot as is_knot, calculateCrossings
import os, os.path, numpy as np, h5py
from numpy import asarray
import atexit
import importlib
from itertools import combinations
import IPython as ipy
import random
import hashlib
from tn_rapprentice import registration as tn_registration
from tn_eval.tps_utils import find_all_normals_naive
from tn_rapprentice.krig_utils import find_rope_normals, find_rope_tangents
from tn_rapprentice import krig_utils as ku
from tn_eval import tps_utils
from tn_rapprentice.registration import tps_rpm_curvature_prior1
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
COLLISION_DIST_THRESHOLD = 0.0
MAX_ACTIONS_TO_TRY = 10 # Number of actions to try (ranked by cost), if TrajOpt trajectory is infeasible
TRAJOPT_MAX_ACTIONS = 5 # Number of actions to compute full feature (TPS + TrajOpt) on
WEIGHTS = np.array([-1])
DS_SIZE = .025
class GlobalVars:
unique_id = 0
actions = None
actions_cache = None
# change to krig?
tps_errors_top10 = []
trajopt_errors_top10 = []
actions_ds_clouds = {}
rope_nodes_crossing_info = {}
def get_action_cloud(sim_env, action, args_eval):
rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
cloud = ropesim.observe_cloud(rope_nodes, sim_env.sim.rope_params.radius, upsample_rad=args_eval.upsample_rad)
return cloud
def get_action_cloud_ds(sim_env, action, args_eval):
if args_eval.downsample:
if action not in GlobalVars.actions_ds_clouds:
GlobalVars.actions_ds_clouds[action] = clouds.downsample(get_action_cloud(sim_env, action, args_eval), DS_SIZE)
return GlobalVars.actions_ds_clouds[action]
else:
return get_action_cloud(sim_env, action, args_eval)
def get_action_rope_nodes(sim_env, action, args_eval):
rope_nodes = GlobalVars.actions[action]['cloud_xyz'][()]
return ropesim.observe_cloud(rope_nodes, sim_env.sim.rope_params.radius, upsample=args_eval.upsample)
def color_cloud(xyz, endpoint_inds, endpoint_color = np.array([0,0,1]), non_endpoint_color = np.array([1,0,0])):
xyzrgb = np.zeros((len(xyz),6))
xyzrgb[:,:3] = xyz
xyzrgb[endpoint_inds,3:] = np.tile(endpoint_color, (endpoint_inds.sum(), 1))
xyzrgb[~endpoint_inds,3:] = np.tile(non_endpoint_color, ((~endpoint_inds).sum(), 1))
return xyzrgb
def redprint(msg):
print colorize.colorize(msg, "red", bold=True)
def yellowprint(msg):
print colorize.colorize(msg, "yellow", bold=True)
def draw_grid(sim_env, old_xyz, f, color = (1,1,0,1)):
grid_means = .5 * (old_xyz.max(axis=0) + old_xyz.min(axis=0))
grid_mins = grid_means - (old_xyz.max(axis=0) - old_xyz.min(axis=0))
grid_maxs = grid_means + (old_xyz.max(axis=0) - old_xyz.min(axis=0))
return plotting_openrave.draw_grid(sim_env.env, f.transform_points, grid_mins, grid_maxs + np.array([0,0,0]), xres = .1, yres = .1, zres = .04, color = color)
def draw_axis(sim_env, hmat):
handles = []
handles.append(sim_env.env.drawarrow(hmat[:3,3], hmat[:3,3]+hmat[:3,0]/10.0, 0.005, (1,0,0,1)))
handles.append(sim_env.env.drawarrow(hmat[:3,3], hmat[:3,3]+hmat[:3,1]/10.0, 0.005, (0,1,0,1)))
handles.append(sim_env.env.drawarrow(hmat[:3,3], hmat[:3,3]+hmat[:3,2]/10.0, 0.005, (0,0,1,1)))
return handles
def draw_finger_pts_traj(sim_env, flr2finger_pts_traj, color):
handles = []
for finger_lr, pts_traj in flr2finger_pts_traj.items():
for pts in pts_traj:
handles.append(sim_env.env.drawlinestrip(np.r_[pts, pts[0][None,:]], 1, color))
return handles
def register_tps(sim_env, state, action, args_eval, interest_pts = None, closing_hmats = None, closing_finger_pts = None):
old_cloud = get_action_cloud_ds(sim_env, action, args_eval)
new_cloud = state[1]
if args_eval.reg_type == 'segment' or 'segment-normal':
old_rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
state_id, new_cloud, new_rope_nodes, _ = state
def plot_cb(rope_nodes0, rope_nodes1, cloud0, cloud1, corr_nm, corr_nm_aug, f, pts_segmentation_inds0, pts_segmentation_inds1):
from rapprentice.plotting_plt import plot_tps_registration_segment_proj_2d
import matplotlib.pyplot as plt
plot_tps_registration_segment_proj_2d(rope_nodes0, rope_nodes1, cloud0, cloud1, corr_nm, corr_nm_aug, f, pts_segmentation_inds0, pts_segmentation_inds1)
if closing_hmats is not None:
plt.subplot(223, aspect='equal')
interest_pts_inds = np.zeros(len(cloud0), dtype=bool)
for hmat in closing_hmats.values():
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, cloud0 - hmat[:3,3]) < 0.025
cloud1_resampled = corr_nm_aug.dot(cloud1)
plt.scatter(cloud1_resampled[interest_pts_inds,0], cloud1_resampled[interest_pts_inds,1], c='none', edgecolors='b', marker='o', s=15)
warped_cloud0 = f.transform_points(cloud0)
plt.scatter(warped_cloud0[interest_pts_inds,0], warped_cloud0[interest_pts_inds,1], c='none', edgecolors='g', marker='o', s=15)
if interest_pts is not None and len(interest_pts) > 0:
plt.subplot(221, aspect='equal')
pts = np.array(interest_pts)
plt.scatter(pts[:,0], pts[:,1], marker='x')
plt.subplot(222, aspect='equal')
pts = f.transform_points(pts)
plt.scatter(pts[:,0], pts[:,1], marker='x')
if closing_hmats is not None:
plt.subplot(221, aspect='equal')
for hmat in closing_hmats.values():
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,0]/10.0, hmat[1,0]/10.0, fc='r', ec='r')
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,1]/10.0, hmat[1,1]/10.0, fc='g', ec='g')
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,2]/10.0, hmat[1,2]/10.0, fc='b', ec='b')
for i_plot in range(2,5):
plt.subplot(2,2,i_plot, aspect='equal')
for hmat in f.transform_hmats(np.array(closing_hmats.values())):
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,0]/10.0, hmat[1,0]/10.0, fc='r', ec='r')
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,1]/10.0, hmat[1,1]/10.0, fc='g', ec='g')
plt.arrow(hmat[0,3], hmat[1,3], hmat[0,2]/10.0, hmat[1,2]/10.0, fc='b', ec='b')
if closing_finger_pts is not None:
import matplotlib
plt.subplot(221, aspect='equal')
lines = []
for pts_list in closing_finger_pts.values():
for pts in pts_list:
lines.append(np.r_[pts, pts[0][None,:]][:,:2])
# lines.append(pts[np.array([True,False,False,True])][:,:2])
lc = matplotlib.collections.LineCollection(lines, colors=(1,0,0), lw=2)
ax = plt.gca()
ax.add_collection(lc)
lines = []
for pts_list in closing_finger_pts.values():
for i_pt in range(4):
closing_pts = mu.interp2d(np.linspace(0,1,20), np.arange(2), np.r_[pts_list[0][i_pt,:][None,:], pts_list[1][3-i_pt,:][None,:]])
lines.append(closing_pts[:,:2])
lc = matplotlib.collections.LineCollection(lines, colors=(1,0,0), lw=1)
ax = plt.gca()
ax.add_collection(lc)
# closing_pts = []
# for pts_list in closing_finger_pts.values():
# for i_pt in range(4):
# closing_pts.append(mu.interp2d(np.linspace(0,1,10), np.arange(2), np.r_[pts_list[0][i_pt,:][None,:], pts_list[1][3-i_pt,:][None,:]]))
# closing_pts = np.concatenate(np.asarray(closing_pts))
# plt.scatter(closing_pts[:,0], closing_pts[:,1], c=(1,0,0), edgecolors=(1,0,0), marker=',', s=1)
lines = []
for pts_list in closing_finger_pts.values():
for pts in pts_list:
pts = f.transform_points(pts)
lines.append(np.r_[pts, pts[0][None,:]][:,:2])
for i_plot in range(2,5):
plt.subplot(2,2,i_plot, aspect='equal')
lc = matplotlib.collections.LineCollection(lines, colors=(0,1,0), lw=2)
ax = plt.gca()
ax.add_collection(lc)
lines = []
for pts_list in closing_finger_pts.values():
for i_pt in range(4):
closing_pts = mu.interp2d(np.linspace(0,1,20), np.arange(2), np.r_[pts_list[0][i_pt,:][None,:], pts_list[1][3-i_pt,:][None,:]])
closing_pts = f.transform_points(closing_pts)
lines.append(closing_pts[:,:2])
for i_plot in range(2,5):
plt.subplot(2,2,i_plot, aspect='equal')
lc = matplotlib.collections.LineCollection(lines, colors=(0,1,0), lw=1)
ax = plt.gca()
ax.add_collection(lc)
plt.show()
x_weights = np.ones(len(old_cloud)) * 1.0/len(old_cloud)
f, corr = tps_registration.tps_segment_registration(old_rope_nodes, new_rope_nodes,
cloud0 = old_cloud, cloud1 = new_cloud, corr_tile_pattern = np.eye(args_eval.upsample_rad),
reg=np.array([0.00015, 0.00015, 0.0015]), x_weights=x_weights, plotting=False, plot_cb=plot_cb)
if corr is not None:
corr = tps_registration.tile(corr, np.eye(args_eval.upsample_rad))
elif args_eval.reg_type == 'rpm':
vis_cost_xy = tps_registration.ab_cost(old_cloud, new_cloud) if args_eval.use_color else None
f, corr = tps_registration.tps_rpm(old_cloud[:,:3], new_cloud[:,:3], vis_cost_xy=vis_cost_xy, user_data={'old_cloud':old_cloud, 'new_cloud':new_cloud})
elif args_eval.reg_type == 'bij':
vis_cost_xy = tps_registration.ab_cost(old_cloud, new_cloud) if args_eval.use_color else None
x_nd = old_cloud[:,:3]
y_md = new_cloud[:,:3]
scaled_x_nd, src_params = registration.unit_boxify(x_nd)
scaled_y_md, targ_params = registration.unit_boxify(y_md)
x_weights = np.ones(len(old_cloud)) * 1.0/len(old_cloud)
f,g = registration.tps_rpm_bij(scaled_x_nd, scaled_y_md, rot_reg=np.r_[1e-4, 1e-4, 1e-1], n_iter=50, reg_init=10, reg_final=.1, x_weights=x_weights, outlierfrac=1e-2, vis_cost_xy=vis_cost_xy)
corr = f._corr
bend_coef = f._bend_coef
rot_coef = f._rot_coef
wt_n = f._wt_n
f = registration.unscale_tps(f, src_params, targ_params)
f._bend_coef = bend_coef
f._rot_coef = rot_coef
f._wt_n = wt_n
return f, corr
def register_tps_cheap(sim_env, state, action, args_eval):
old_cloud = get_action_cloud_ds(sim_env, action, args_eval)
new_cloud = state[1]
if args_eval.reg_type == 'segment':
old_rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
old_rope_nodes_hash = hashlib.sha1(old_rope_nodes).hexdigest()
if action not in GlobalVars.rope_nodes_crossing_info:
if action not in GlobalVars.actions_cache:
action_group = GlobalVars.actions_cache.create_group(action)
else:
action_group = GlobalVars.actions_cache[action]
if old_rope_nodes_hash not in action_group:
action_rope_nodes_group = action_group.create_group(old_rope_nodes_hash)
crossings, crossings_links_inds, cross_pairs, rope_closed = calculateCrossings(old_rope_nodes)
action_rope_nodes_group['rope_nodes'] = old_rope_nodes
if crossings: action_rope_nodes_group['crossings'] = crossings
if crossings_links_inds: action_rope_nodes_group['crossings_links_inds'] = crossings_links_inds
if cross_pairs: action_rope_nodes_group['cross_pairs'] = list(cross_pairs)
action_rope_nodes_group['rope_closed'] = rope_closed
else:
action_rope_nodes_group = action_group[old_rope_nodes_hash]
assert np.all(old_rope_nodes == action_rope_nodes_group['rope_nodes'][()])
crossings = action_rope_nodes_group['crossings'][()] if 'crossings' in action_rope_nodes_group else []
crossings_links_inds = action_rope_nodes_group['crossings_links_inds'][()] if 'crossings_links_inds' in action_rope_nodes_group else []
cross_pairs = set([tuple(p) for p in action_rope_nodes_group['cross_pairs']]) if 'cross_pairs' in action_rope_nodes_group else set([])
rope_closed = action_rope_nodes_group['rope_closed'][()]
GlobalVars.rope_nodes_crossing_info[action] = (old_rope_nodes, crossings, crossings_links_inds, cross_pairs, rope_closed)
state_id, new_cloud, new_rope_nodes = state
if state_id not in GlobalVars.rope_nodes_crossing_info:
crossings, crossings_links_inds, cross_pairs, rope_closed = calculateCrossings(new_rope_nodes)
GlobalVars.rope_nodes_crossing_info[state_id] = (new_rope_nodes, crossings, crossings_links_inds, cross_pairs, rope_closed)
def plot_cb(rope_nodes0, rope_nodes1, corr_nm, f, pts_segmentation_inds0, pts_segmentation_inds1):
from rapprentice.plotting_plt import plot_tps_registration_segment_proj_2d
import matplotlib.pyplot as plt
plot_tps_registration_segment_proj_2d(rope_nodes0, rope_nodes1, corr_nm, f, pts_segmentation_inds0, pts_segmentation_inds1)
plt.show()
x_weights = np.ones(len(old_cloud)) * 1.0/len(old_cloud)
f, corr = tps_registration.tps_segment_registration(GlobalVars.rope_nodes_crossing_info[action], GlobalVars.rope_nodes_crossing_info[state_id],
cloud0 = old_cloud, cloud1 = new_cloud, corr_tile_pattern = np.eye(args_eval.upsample_rad),
reg=np.array([0.00015, 0.00015, 0.0015]), x_weights=x_weights, plotting=False, plot_cb=plot_cb)
#ipy.embed()
elif args_eval.reg_type == 'segment-normal':
old_rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
old_rope_nodes_hash = hashlib.sha1(old_rope_nodes).hexdigest()
if action not in GlobalVars.rope_nodes_crossing_info:
if action not in GlobalVars.actions_cache:
action_group = GlobalVars.actions_cache.create_group(action)
else:
action_group = GlobalVars.actions_cache[action]
if old_rope_nodes_hash not in action_group:
action_rope_nodes_group = action_group.create_group(old_rope_nodes_hash)
crossings, crossings_links_inds, cross_pairs, rope_closed = calculateCrossings(old_rope_nodes)
action_rope_nodes_group['rope_nodes'] = old_rope_nodes
if crossings: action_rope_nodes_group['crossings'] = crossings
if crossings_links_inds: action_rope_nodes_group['crossings_links_inds'] = crossings_links_inds
if cross_pairs: action_rope_nodes_group['cross_pairs'] = list(cross_pairs)
action_rope_nodes_group['rope_closed'] = rope_closed
else:
action_rope_nodes_group = action_group[old_rope_nodes_hash]
assert np.all(old_rope_nodes == action_rope_nodes_group['rope_nodes'][()])
crossings = action_rope_nodes_group['crossings'][()] if 'crossings' in action_rope_nodes_group else []
crossings_links_inds = action_rope_nodes_group['crossings_links_inds'][()] if 'crossings_links_inds' in action_rope_nodes_group else []
cross_pairs = set([tuple(p) for p in action_rope_nodes_group['cross_pairs']]) if 'cross_pairs' in action_rope_nodes_group else set([])
rope_closed = action_rope_nodes_group['rope_closed'][()]
GlobalVars.rope_nodes_crossing_info[action] = (old_rope_nodes, crossings, crossings_links_inds, cross_pairs, rope_closed)
state_id, new_cloud, new_rope_nodes = state
if state_id not in GlobalVars.rope_nodes_crossing_info:
crossings, crossings_links_inds, cross_pairs, rope_closed = calculateCrossings(new_rope_nodes)
GlobalVars.rope_nodes_crossing_info[state_id] = (new_rope_nodes, crossings, crossings_links_inds, cross_pairs, rope_closed)
def plot_cb(rope_nodes0, rope_nodes1, corr_nm, f, pts_segmentation_inds0, pts_segmentation_inds1):
from rapprentice.plotting_plt import plot_tps_registration_segment_proj_2d
import matplotlib.pyplot as plt
plot_tps_registration_segment_proj_2d(rope_nodes0, rope_nodes1, corr_nm, f, pts_segmentation_inds0, pts_segmentation_inds1)
plt.show()
x_weights = np.ones(len(old_cloud)) * 1.0/len(old_cloud)
_, corr = tps_registration.tps_segment_registration(GlobalVars.rope_nodes_crossing_info[action], GlobalVars.rope_nodes_crossing_info[state_id],
cloud0 = old_cloud, cloud1 = new_cloud, corr_tile_pattern = np.eye(args_eval.upsample_rad),
reg=np.array([0.00015, 0.00015, 0.0015]), x_weights=x_weights, plotting=False, plot_cb=plot_cb)
#ipy.embed()
if corr is not None:
seg_info = GlobalVars.actions[action]
closing_inds = get_closing_inds(seg_info)
closing_hmats = {}
for lr in closing_inds:
if closing_inds[lr] != -1:
closing_hmats[lr] = seg_info["%s_gripper_tool_frame"%lr]['hmat'][closing_inds[lr]]
interest_pts_inds = np.zeros(len(old_cloud), dtype=bool)
try:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats['l'][:3,3]) < 0.05
except:
print None #'I need to figure out how to use try without except'
try:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats['r'][:3,3]) < 0.05
except:
print None #'I need to figure out how to use try without except'
#ipy.embed()
x_na = old_cloud
y_ng = corr.dot(new_cloud)
xtangents = find_rope_tangents(x_na)
ytangents = find_rope_tangents(y_ng)
xnormals = xtangents.copy()
ynormals = ytangents.copy()
xnormals[:,0], xnormals[:,1] = -xnormals[:,1], xnormals[:,0]
ynormals[:,0], ynormals[:,1] = -ynormals[:,1], ynormals[:,0]
#Epts = np.r_[x_na, x_na]
#exs = np.r_[xtangents, xnormals]
#eys = np.r_[ytangents, ynormals]
Epts = x_na[interest_pts_inds]
exs = xnormals[interest_pts_inds]
eys = ynormals[interest_pts_inds]
normal_coef = args_eval.normal_coef
f = tn_registration.fit_KrigingSpline(x_na, Epts, exs, y_ng, eys, bend_coef = .1, normal_coef = normal_coef)
else:
f = None
elif args_eval.reg_type == 'rpm':
vis_cost_xy = tps_registration.ab_cost(old_cloud, new_cloud) if args_eval.use_color else None
f, corr = tps_registration.tps_rpm(old_cloud[:,:3], new_cloud[:,:3], n_iter=14, em_iter=1, vis_cost_xy=vis_cost_xy, user_data={'old_cloud':old_cloud, 'new_cloud':new_cloud})
elif args_eval.reg_type == 'bij':
vis_cost_xy = tps_registration.ab_cost(old_cloud, new_cloud) if args_eval.use_color else None
x_nd = old_cloud[:,:3]
y_md = new_cloud[:,:3]
scaled_x_nd, src_params = registration.unit_boxify(x_nd)
scaled_y_md, targ_params = registration.unit_boxify(y_md)
f,g = registration.tps_rpm_bij(scaled_x_nd, scaled_y_md, rot_reg=1e-3, n_iter=10, vis_cost_xy=vis_cost_xy)
corr = f._corr
elif args_eval.reg_type == 'curve-rpm':
EM_iter = 1
beta = 20 #20 works for 90 rotation
wsize = .1
T_init = .04
T_final = .00004
bend_init = 1 # 1e2 works for 90 rotation
bend_final = .001
DS_SIZE = .01
wsize = args_eval.wsize
x_nd = old_cloud[:, :3]
big_old_cloud = GlobalVars.actions[action]['old_cloud_xyz'][()]
y_md = new_cloud[:, :3]
big_new_cloud, endpoint_inds = state[3]
np.set_printoptions(threshold=np.nan)
big_new_cloud_ds = clouds.downsample(big_new_cloud, DS_SIZE)
#ipy.embed()
f , corr = tn_registration.tps_rpm_curvature_prior1(x_nd, y_md, orig_source = big_old_cloud, orig_target = big_new_cloud_ds, n_iter = 14, EM_iter = EM_iter, T_init = T_init, T_final = T_final, bend_init = bend_init, bend_final = bend_final, wsize = wsize, beta = beta)
return f, corr
def compute_trans_traj(sim_env, state_or_get_state_fn, action, i_step, args_eval, transferopt=None, animate=False, interactive=False, simulate=True, replay_full_trajs=None):
alpha = args_eval.alpha
beta_pos = args_eval.beta_pos
beta_rot = args_eval.beta_rot
gamma = args_eval.gamma
windowsize = args_eval.windowsize
normal_coef = args_eval.normal_coef
if transferopt is None:
transferopt = args_eval.transferopt
seg_info = GlobalVars.actions[action]
if simulate:
sim_util.reset_arms_to_side(sim_env)
cloud_dim = 6 if args_eval.use_color else 3
old_cloud = get_action_cloud_ds(sim_env, action, args_eval)[:,:cloud_dim]
big_old_cloud = GlobalVars.actions[action]['old_cloud_xyz'][()]
old_rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
n, d = old_cloud.shape
closing_inds = get_closing_inds(seg_info)
closing_hmats = {}
for lr in closing_inds:
if closing_inds[lr] != -1:
closing_hmats[lr] = seg_info["%s_gripper_tool_frame"%lr]['hmat'][closing_inds[lr]]
miniseg_intervals = []
for lr in 'lr':
miniseg_intervals.extend([(i_miniseg_lr, lr, i_start, i_end) for (i_miniseg_lr, (i_start, i_end)) in enumerate(zip(*sim_util.split_trajectory_by_lr_gripper(seg_info, lr)))])
# sort by the start of the trajectory, then by the length (if both trajectories start at the same time, the shorter one should go first), and then break ties by executing the right trajectory first
miniseg_intervals = sorted(miniseg_intervals, key=lambda (i_miniseg_lr, lr, i_start, i_end): (i_start, i_end-i_start, {'l':'r', 'r':'l'}[lr]))
miniseg_interval_groups = []
for (curr_miniseg_interval, next_miniseg_interval) in zip(miniseg_intervals[:-1], miniseg_intervals[1:]):
curr_i_miniseg_lr, curr_lr, curr_i_start, curr_i_end = curr_miniseg_interval
next_i_miniseg_lr, next_lr, next_i_start, next_i_end = next_miniseg_interval
if len(miniseg_interval_groups) > 0 and curr_miniseg_interval in miniseg_interval_groups[-1]:
continue
curr_gripper_open = sim_util.binarize_gripper(seg_info["%s_gripper_joint"%curr_lr][curr_i_end])
next_gripper_open = sim_util.binarize_gripper(seg_info["%s_gripper_joint"%next_lr][next_i_end])
miniseg_interval_group = [curr_miniseg_interval]
if not curr_gripper_open and not next_gripper_open and curr_lr != next_lr and curr_i_start < next_i_end and next_i_start < curr_i_end:
miniseg_interval_group.append(next_miniseg_interval)
miniseg_interval_groups.append(miniseg_interval_group)
success = True
feasible = True
misgrasp = False
full_trajs = []
obj_values = []
for i_miniseg_group, miniseg_interval_group in enumerate(miniseg_interval_groups):
if type(state_or_get_state_fn) == tuple:
state = state_or_get_state_fn
else:
state = state_or_get_state_fn(sim_env)
if state is None: break
_, new_cloud, new_rope_nodes, (big_new_cloud, endpoint_inds) = state
new_cloud = new_cloud[:,:cloud_dim]
#big_new_cloud, endpoint_inds = sim_env.sim.raycast_cloud(endpoints=3)
handles = []
if animate:
# color code: r demo, y transformed, g transformed resampled, b new
handles.append(sim_env.env.plot3(old_cloud[:,:3], 2, (1,0,0)))
handles.append(sim_env.env.plot3(new_cloud[:,:3], 2, new_cloud[:,3:] if args_eval.use_color else (0,0,1)))
sim_env.viewer.Step()
if not simulate or replay_full_trajs is None: # we are not simulating, we still want to compute the costs
group_full_trajs = []
for (i_miniseg_lr, lr, i_start, i_end) in miniseg_interval_group:
manip_name = {"l":"leftarm", "r":"rightarm"}[lr]
ee_link_name = "%s_gripper_tool_frame"%lr
################################
redprint("Generating %s arm joint trajectory for part %i"%(lr, i_miniseg_lr))
ipy.embed()
# figure out how we're gonna resample stuff
old_arm_traj = asarray(seg_info[manip_name][i_start - int(i_start > 0):i_end+1])
#ipy.embed()
if not sim_util.arm_moved(old_arm_traj):
continue
old_finger_traj = sim_util.gripper_joint2gripper_l_finger_joint_values(seg_info['%s_gripper_joint'%lr][i_start - int(i_start > 0):i_end+1])[:,None]
JOINT_LENGTH_PER_STEP = .1
_, timesteps_rs = sim_util.unif_resample(old_arm_traj, JOINT_LENGTH_PER_STEP)
### Generate fullbody traj
old_arm_traj_rs = mu.interp2d(timesteps_rs, np.arange(len(old_arm_traj)), old_arm_traj)
old_rope_nodes = get_action_rope_nodes(sim_env, action, args_eval)
x_weights = np.ones(len(old_cloud)) * 1.0/len(old_cloud)
#ipy.embed()
#xtangents = find_rope_tangents(x_na)
#ytangents = find_rope_tangents(y_ng)
if args_eval.use_normals:
_, corr = register_tps_cheap(sim_env, state, action, args_eval)
bend_coef = args_eval.bend_coef
rot_coef = 1e-5
wsize = args_eval.wsize
pld = args_eval.pld
wt_n = x_weights.copy()
if corr is None:
success = True
break
x_na = old_cloud
y_ng = (corr/corr.sum(axis=1)[:,None]).dot(new_cloud)
interest_pts_inds = np.zeros(len(old_cloud), dtype=bool)
radius = 5e-4
while not np.any(interest_pts_inds) and radius < .5:
if lr in closing_hmats:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats[lr][:3,3]) < radius
radius += 5e-4
print radius
if np.any(interest_pts_inds):
assert len(x_na[interest_pts_inds]) == 1
interest_pts_tangents = np.zeros((len(x_na)), dtype=bool)
if lr in closing_hmats:
interest_pts_tangents += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats[lr][:3, 3]) < .05
#ipy.embed()
# need to upsample for pld to work on big_old_cloud
#source_normals = find_all_normals_naive(old_cloud[interest_pts_tangents], big_old_cloud, wsize = wsize, project_lower_dim = pld)
source_normals = find_all_normals_naive(old_cloud[interest_pts_tangents][:, :2], big_old_cloud[:,:2], wsize = wsize, project_lower_dim = False)
source_normals = np.c_[source_normals, np.zeros(len(source_normals))]
target_normals = find_all_normals_naive(y_ng[interest_pts_tangents][:, :2], big_new_cloud[:, :2], wsize = wsize, project_lower_dim = False)
target_normals = np.c_[target_normals, np.zeros(len(target_normals))]
wt_n = x_weights.copy()
#### flip_normals might be weird
target_normals = tps_utils.flip_normals(x_na, x_na[interest_pts_tangents], source_normals, y_ng, target_normals, bend_coef = .1)
znormals = np.zeros((x_na[interest_pts_tangents].shape))
znormals[:,2] = np.ones((x_na[interest_pts_tangents].shape[0]))
Epts = np.r_[x_na[interest_pts_tangents], x_na[interest_pts_tangents]]
exs = np.r_[source_normals, znormals]
eys = np.r_[target_normals, znormals]
interest_pts_inds1 = np.r_[interest_pts_inds, np.zeros(2*len(x_na[interest_pts_tangents]), dtype=bool)]
wt_nt = wt_n.copy()
wt_nt[interest_pts_inds] *= 1
wt_nn = np.r_[wt_n, wt_nt[interest_pts_tangents], wt_nt[interest_pts_tangents]]
interest_pts_for_loop = interest_pts_inds[interest_pts_tangents]
#xnormal = xtangents[interest_pts_inds].copy()
#xnormal[:,1], xnormal[:,0] = xnormal[:,0], -xnormal[:,1]
#ynormal = ytangents[interest_pts_inds].copy()
#ynormal[:,1], ynormal[:,0] = ynormal[:,0], -ynormal[:,1]
#exs[interest_pts_inds] = xnormal
#eys[interest_pts_inds] = ynormal
#ipy.embed()
f = tn_registration.fit_KrigingSpline_Interest(x_na, Epts, exs, y_ng, eys, bend_coef = bend_coef, normal_coef = normal_coef, interest_pts_inds = interest_pts_inds1, wt_n = wt_nn)
if np.any(interest_pts_inds):
for _ in range(5):
#ipy.embed()
interest_pts_errs = tps_utils.angle_difference(f.transform_normals(x_na[interest_pts_for_loop,:], exs[interest_pts_for_loop, :]), eys[interest_pts_for_loop,:].T)
print interest_pts_errs
if interest_pts_errs < 30:
break
redprint("TPS fitting: Gripper is approaching from bad angle. Increasing penalty for these weights.")
wt_nt[interest_pts_inds] += .1
wt_nn = np.r_[wt_n, wt_nt[interest_pts_tangents], wt_nt[interest_pts_tangents]]
f = tn_registration.fit_KrigingSpline_Interest(x_na, Epts, exs, y_ng, eys, bend_coef = bend_coef, normal_coef = normal_coef, interest_pts_inds = interest_pts_inds1, wt_n = wt_nn)
else:
f, corr = register_tps(sim_env, state, action, args_eval)
if f is None: break
x_na = old_cloud
y_ng = (corr/corr.sum(axis=1)[:,None]).dot(new_cloud)
bend_coef = f._bend_coef
rot_coef = f._rot_coef
wt_n = f._wt_n.copy()
interest_pts_inds = np.zeros(len(old_cloud), dtype=bool)
if lr in closing_hmats:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats[lr][:3,3]) < 0.05
interest_pts_err_tol = 0.0025
max_iters = 5 if transferopt != "pose" else 0
penalty_factor = 10.0
if np.any(interest_pts_inds):
for _ in range(max_iters):
interest_pts_errs = np.apply_along_axis(np.linalg.norm, 1, (f.transform_points(x_na[interest_pts_inds,:]) - y_ng[interest_pts_inds,:]))
if np.all(interest_pts_errs < interest_pts_err_tol):
break
redprint("TPS fitting: The error of the interest points is above the tolerance. Increasing penalty for these weights.")
wt_n[interest_pts_inds] *= penalty_factor
f = registration.fit_ThinPlateSpline(x_na, y_ng, bend_coef, rot_coef, wt_n)
if animate:
handles.append(sim_env.env.plot3(f.transform_points(old_cloud[:,:3]), 2, old_cloud[:,3:] if args_eval.use_color else (1,1,0)))
new_cloud_rs = corr.dot(new_cloud)
handles.append(sim_env.env.plot3(new_cloud_rs[:,:3], 2, new_cloud_rs[:,3:] if args_eval.use_color else (0,1,0)))
handles.extend(draw_grid(sim_env, old_cloud[:,:3], f))
sim_env.viewer.Step()
#ipy.embed()
old_ee_traj = asarray(seg_info["%s_gripper_tool_frame"%lr]['hmat'][i_start - int(i_start > 0):i_end+1])
transformed_ee_traj = f.transform_hmats(old_ee_traj)
transformed_ee_traj_rs = np.asarray(resampling.interp_hmats(timesteps_rs, np.arange(len(transformed_ee_traj)), transformed_ee_traj))
if animate:
handles.append(sim_env.env.drawlinestrip(old_ee_traj[:,:3,3], 2, (1,0,0)))
handles.append(sim_env.env.drawlinestrip(transformed_ee_traj[:,:3,3], 2, (1,1,0)))
handles.append(sim_env.env.drawlinestrip(transformed_ee_traj_rs[:,:3,3], 2, (0,1,0)))
sim_env.viewer.Step()
print "planning pose trajectory following"
dof_inds = sim_util.dof_inds_from_name(sim_env.robot, manip_name)
joint_ind = sim_env.robot.GetJointIndex("%s_shoulder_lift_joint"%lr)
init_arm_traj = old_arm_traj_rs.copy()
init_arm_traj[:,dof_inds.index(joint_ind)] = sim_env.robot.GetDOFLimits([joint_ind])[0][0]
# might need to change this to krig
new_arm_traj, obj_value, pose_errs = planning.plan_follow_traj(sim_env.robot, manip_name, sim_env.robot.GetLink(ee_link_name), transformed_ee_traj_rs, init_arm_traj,
start_fixed=i_miniseg_lr!=0,
beta_pos=beta_pos, beta_rot=beta_rot)
if transferopt == 'finger' or transferopt == 'joint':
old_ee_traj_rs = np.asarray(resampling.interp_hmats(timesteps_rs, np.arange(len(old_ee_traj)), old_ee_traj))
old_finger_traj_rs = mu.interp2d(timesteps_rs, np.arange(len(old_finger_traj)), old_finger_traj)
flr2old_finger_pts_traj_rs = sim_util.get_finger_pts_traj(sim_env, lr, (old_ee_traj_rs, old_finger_traj_rs))
flr2transformed_finger_pts_traj_rs = {}
flr2finger_link = {}
flr2finger_rel_pts = {}
for finger_lr in 'lr':
flr2transformed_finger_pts_traj_rs[finger_lr] = f.transform_points(np.concatenate(flr2old_finger_pts_traj_rs[finger_lr], axis=0)).reshape((-1,4,3))
flr2finger_link[finger_lr] = sim_env.robot.GetLink("%s_gripper_%s_finger_tip_link"%(lr,finger_lr))
flr2finger_rel_pts[finger_lr] = sim_util.get_finger_rel_pts(finger_lr)
if animate:
handles.extend(draw_finger_pts_traj(sim_env, flr2old_finger_pts_traj_rs, (1,0,0)))
handles.extend(draw_finger_pts_traj(sim_env, flr2transformed_finger_pts_traj_rs, (0,1,0)))
sim_env.viewer.Step()
# enable finger DOF and extend the trajectories to include the closing part only if the gripper closes at the end of this minisegment
next_gripper_open = sim_util.binarize_gripper(seg_info["%s_gripper_joint"%lr][i_end+1]) if i_end+1 < len(seg_info["%s_gripper_joint"%lr]) else True
if not sim_env.sim.is_grabbing_rope(lr) and not next_gripper_open:
manip_name = manip_name + "+" + "%s_gripper_l_finger_joint"%lr
old_finger_closing_traj_start = old_finger_traj_rs[-1][0]
old_finger_closing_traj_target = sim_util.get_binary_gripper_angle(sim_util.binarize_gripper(seg_info["%s_gripper_joint"%lr][i_end+1]))
old_finger_closing_traj_rs = np.linspace(old_finger_closing_traj_start, old_finger_closing_traj_target, np.ceil(abs(old_finger_closing_traj_target - old_finger_closing_traj_start) / .02))[:,None]
closing_n_steps = len(old_finger_closing_traj_rs)
old_ee_closing_traj_rs = np.tile(old_ee_traj_rs[-1], (closing_n_steps,1,1))
flr2old_finger_pts_closing_traj_rs = sim_util.get_finger_pts_traj(sim_env, lr, (old_ee_closing_traj_rs, old_finger_closing_traj_rs))
init_traj = np.r_[np.c_[new_arm_traj, old_finger_traj_rs],
np.c_[np.tile(new_arm_traj[-1], (closing_n_steps,1)), old_finger_closing_traj_rs]]
flr2transformed_finger_pts_closing_traj_rs = {}
for finger_lr in 'lr':
flr2old_finger_pts_traj_rs[finger_lr] = np.r_[flr2old_finger_pts_traj_rs[finger_lr], flr2old_finger_pts_closing_traj_rs[finger_lr]]
flr2transformed_finger_pts_closing_traj_rs[finger_lr] = f.transform_points(np.concatenate(flr2old_finger_pts_closing_traj_rs[finger_lr], axis=0)).reshape((-1,4,3))
flr2transformed_finger_pts_traj_rs[finger_lr] = np.r_[flr2transformed_finger_pts_traj_rs[finger_lr],
flr2transformed_finger_pts_closing_traj_rs[finger_lr]]
if animate:
handles.extend(draw_finger_pts_traj(sim_env, flr2old_finger_pts_closing_traj_rs, (1,0,0)))
handles.extend(draw_finger_pts_traj(sim_env, flr2transformed_finger_pts_closing_traj_rs, (0,1,0)))
#ipy.embed()
#sim_env.viewer.Idle()
sim_env.viewer.Step()
else:
init_traj = new_arm_traj
print "planning finger points trajectory following"
# change to krig
new_traj, obj_value, pose_errs = planning.plan_follow_finger_pts_traj(sim_env.robot, manip_name, flr2finger_link, flr2finger_rel_pts, flr2transformed_finger_pts_traj_rs, init_traj,
start_fixed=i_miniseg_lr!=0,
beta_pos=beta_pos, gamma=gamma)
if transferopt == 'joint':
print "planning joint TPS and finger points trajectory following"
#change to krig
new_traj, f, new_N_z, \
obj_value, rel_pts_costs, tps_cost = planning.joint_fit_tps_follow_finger_pts_traj(sim_env.robot, manip_name, flr2finger_link, flr2finger_rel_pts, flr2old_finger_pts_traj_rs, new_traj,
x_na, y_ng, bend_coef, rot_coef, wt_n, old_N_z=None,
start_fixed=i_miniseg_lr!=0,
alpha=alpha, beta_pos=beta_pos, gamma=gamma)
"""
if np.any(interest_pts_inds):
for _ in range(max_iters):
interest_pts_errs = np.apply_along_axis(np.linalg.norm, 1, (f.transform_points(x_na[interest_pts_inds,:]) - y_ng[interest_pts_inds,:]))
if np.all(interest_pts_errs < interest_pts_err_tol):
break
redprint("Joint TPS fitting: The error of the interest points is above the tolerance. Increasing penalty for these weights.")
wt_n[interest_pts_inds] *= penalty_factor
# change to krig
new_traj, f, new_N_z, \
obj_value, rel_pts_costs, tps_cost = planning.joint_fit_tps_follow_finger_pts_traj(sim_env.robot, manip_name, flr2finger_link, flr2finger_rel_pts, flr2old_finger_pts_traj_rs, new_traj,
x_na, y_ng, bend_coef, rot_coef, wt_n, old_N_z=new_N_z,
start_fixed=i_miniseg_lr!=0,
alpha=alpha, beta_pos=beta_pos, gamma=gamma)
"""
else:
if args_eval.use_normals:
obj_value += alpha * planning.krig_obj(f, x_na, y_ng, exs, eys, Epts, bend_coef, rot_coef, wt_nn)
else:
obj_value += alpha * planning.tps_obj(f, x_na, y_ng, bend_coef, rot_coef, wt_n)
if animate:
flr2new_transformed_finger_pts_traj_rs = {}
for finger_lr in 'lr':
flr2new_transformed_finger_pts_traj_rs[finger_lr] = f.transform_points(np.concatenate(flr2old_finger_pts_traj_rs[finger_lr], axis=0)).reshape((-1,4,3))
handles.extend(draw_finger_pts_traj(sim_env, flr2new_transformed_finger_pts_traj_rs, (0,1,1)))
sim_env.viewer.Step()
else:
new_traj = new_arm_traj
obj_values.append(obj_value)
f._bend_coef = bend_coef
f._rot_coef = rot_coef
f._wt_n = wt_n
full_traj = (new_traj, sim_util.dof_inds_from_name(sim_env.robot, manip_name))
group_full_trajs.append(full_traj)
if animate:
handles.append(sim_env.env.drawlinestrip(sim_util.get_ee_traj(sim_env, lr, full_traj)[:,:3,3], 2, (0,0,1)))
flr2new_finger_pts_traj = sim_util.get_finger_pts_traj(sim_env, lr, full_traj)
handles.extend(draw_finger_pts_traj(sim_env, flr2new_finger_pts_traj, (0,0,1)))
sim_env.viewer.Step()
full_traj = sim_util.merge_full_trajs(group_full_trajs)
else:
full_traj = replay_full_trajs[i_miniseg_group]
full_trajs.append(full_traj)
if not simulate:
if not eval_util.traj_is_safe(sim_env, full_traj, COLLISION_DIST_THRESHOLD, upsample=100):
return np.inf
else:
continue
for (i_miniseg_lr, lr, _, _) in miniseg_interval_group:
redprint("Executing %s arm joint trajectory for part %i"%(lr, i_miniseg_lr))
if len(full_traj[0]) > 0:
if not eval_util.traj_is_safe(sim_env, full_traj, COLLISION_DIST_THRESHOLD, upsample=100):
redprint("Trajectory not feasible")
feasible = False
success = False
else: # Only execute feasible trajectories
first_miniseg = True
for (i_miniseg_lr, _, _, _) in miniseg_interval_group:
first_miniseg &= i_miniseg_lr == 0
if len(full_traj[0]) > 0:
success &= sim_util.sim_full_traj_maybesim(sim_env, full_traj, animate=animate, interactive=interactive, max_cart_vel_trans_traj=.05 if first_miniseg else .02)
#sim_env.viewer.Idle()
if not success: break
for (i_miniseg_lr, lr, i_start, i_end) in miniseg_interval_group:
next_gripper_open = sim_util.binarize_gripper(seg_info["%s_gripper_joint"%lr][i_end+1]) if i_end+1 < len(seg_info["%s_gripper_joint"%lr]) else True
curr_gripper_open = sim_util.binarize_gripper(seg_info["%s_gripper_joint"%lr][i_end])
if not sim_util.set_gripper_maybesim(sim_env, lr, next_gripper_open, curr_gripper_open, animate=animate):
redprint("Grab %s failed" % lr)
misgrasp = True
success = False
#ipy.embed()
if not success: break
if not simulate:
return np.sum(obj_values)
sim_env.sim.settle(animate=animate)
sim_env.sim.release_rope('l')
sim_env.sim.release_rope('r')
sim_util.reset_arms_to_side(sim_env)
if animate:
sim_env.viewer.Step()
return success, feasible, misgrasp, full_trajs
#change to krig
def regcost_feature_fn(sim_env, state, action, args_eval):
# change to krig
f, corr = register_tps_cheap(sim_env, state, action, args_eval)
if f is None:
cost = np.inf
else:
# change to krig
if args_eval.reg_type == 'segment-normal':
#ipy.embed()
seg_info = GlobalVars.actions[action]
closing_inds = get_closing_inds(seg_info)
closing_hmats = {}
for lr in closing_inds:
if closing_inds[lr] != -1:
closing_hmats[lr] = seg_info["%s_gripper_tool_frame"%lr]['hmat'][closing_inds[lr]]
old_cloud = get_action_cloud_ds(sim_env, action, args_eval)
new_cloud = state[1]
interest_pts_inds = np.zeros(len(old_cloud), dtype=bool)
try:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats['l'][:3,3]) < 0.05
except:
print None #'I need to figure out how to use try without except'
try:
interest_pts_inds += np.apply_along_axis(np.linalg.norm, 1, old_cloud - closing_hmats['r'][:3,3]) < 0.05
except:
print None #'I need to figure out how to use try without except'
x_na = old_cloud
y_ng = corr.dot(new_cloud)
xtangents = find_rope_tangents(x_na)
ytangents = find_rope_tangents(y_ng)
xnormals = xtangents.copy()
ynormals = ytangents.copy()
xnormals[:,0], xnormals[:,1] = -xnormals[:,1], xnormals[:,0]
ynormals[:,0], ynormals[:,1] = -ynormals[:,1], ynormals[:,0]
#Epts = np.r_[x_na, x_na]
#exs = np.r_[xtangents, xnormals]
#eys = np.r_[ytangents, ynormals]
Epts = x_na[interest_pts_inds]
exs = xnormals[interest_pts_inds]
eys = ynormals[interest_pts_inds]
normal_coef = args_eval.normal_coef
weights = np.ones(((len(x_na)+len(exs)), 1))
weights[len(x_na):] *= 1
cost = planning.krig_obj(f, x_na, y_ng, exs, eys, Epts, 5, 1e-5, weights)
else:
cost = registration.tps_reg_cost(f)
return np.array([float(cost)]) # no need to normalize since bending cost is independent of number of points
def regcost_trajopt_feature_fn(sim_env, state, action, args_eval):
obj_values_sum = compute_trans_traj(sim_env, state, action, None, args_eval, simulate=False, transferopt='finger')
return np.array([obj_values_sum])
def jointopt_feature_fn(sim_env, state, action, args_eval):
obj_values_sum = compute_trans_traj(sim_env, state, action, None, args_eval, simulate=False, transferopt='joint')
return np.array([obj_values_sum])
def q_value_fn(state, action, sim_env, fn):
return np.dot(WEIGHTS, fn(sim_env, state, action)) #+ w0
def select_feature_fn(warping_cost, args_eval):
if warping_cost == "regcost":
feature_fn = lambda sim_env, state, action: regcost_feature_fn(sim_env, state, action, args_eval)
elif warping_cost == "regcost-trajopt":
feature_fn = lambda sim_env, state, action: regcost_trajopt_feature_fn(sim_env, state, action, args_eval)
elif warping_cost == "jointopt":
feature_fn = lambda sim_env, state, action: jointopt_feature_fn(sim_env, state, action, args_eval)
else:
raise RuntimeError("Invalid warping cost")
return feature_fn
def get_unique_id():
GlobalVars.unique_id += 1
return GlobalVars.unique_id - 1
def get_state(sim_env, args_eval):
if args_eval.raycast:
new_cloud_rc, endpoint_inds = sim_env.sim.raycast_cloud(endpoints=3)
if new_cloud_rc.shape[0] == 0: # rope is not visible (probably because it fall off the table)
return None
new_cloud = sim_env.sim.observe_cloud(upsample=args_eval.upsample, upsample_rad=args_eval.upsample_rad)
else:
new_cloud = sim_env.sim.observe_cloud(upsample=args_eval.upsample, upsample_rad=args_eval.upsample_rad)
endpoint_inds = np.zeros(len(new_cloud), dtype=bool) # for now, args_eval.raycast=False is not compatible with args_eval.use_color=True
new_cloud_rc, endpoint_inds = None, None
if args_eval.use_color:
new_cloud = color_cloud(new_cloud, endpoint_inds)
new_cloud_ds = clouds.downsample(new_cloud, DS_SIZE) if args_eval.downsample else new_cloud
new_rope_nodes = sim_env.sim.rope.GetControlPoints()
new_rope_nodes= ropesim.observe_cloud(new_rope_nodes, sim_env.sim.rope_params.radius, upsample=args_eval.upsample)
state = ("eval_%i"%get_unique_id(), new_cloud_ds, new_rope_nodes, (new_cloud_rc, endpoint_inds))
return state
def select_best_action(sim_env, state, num_actions_to_try, feature_fn, prune_feature_fn, eval_stats, warpingcost):
print "Choosing an action"
num_top_actions = max(num_actions_to_try, TRAJOPT_MAX_ACTIONS)
#ipy.embed()
start_time = time.time()
q_values_prune = [(q_value_fn(state, action, sim_env, prune_feature_fn), action) for action in GlobalVars.actions]
agenda_top_actions = sorted(q_values_prune, key = lambda v: -v[0])[:num_top_actions]
if feature_fn == prune_feature_fn:
q_values = q_values_prune
agenda = agenda_top_actions
else:
if len(agenda_top_actions) > TRAJOPT_MAX_ACTIONS:
agenda_top_actions = agenda_top_actions[:TRAJOPT_MAX_ACTIONS]
q_values = [(q_value_fn(state, a, sim_env, feature_fn), a) for (v, a) in agenda_top_actions]
agenda = sorted(q_values, key = lambda v: -v[0])
eval_stats.action_elapsed_time += time.time() - start_time
q_values_root = [q for (q, a) in q_values]
return agenda, q_values_root
def eval_on_holdout(args, sim_env):
feature_fn = select_feature_fn(args.eval.warpingcost, args.eval)
if args.eval.warpingcost == 'regcost':
prune_feature_fn = feature_fn # so that we can check for function equality
else:
prune_feature_fn = select_feature_fn('regcost', args.eval)
holdoutfile = h5py.File(args.eval.holdoutfile, 'r')
holdout_items = eval_util.get_holdout_items(holdoutfile, args.tasks, args.taskfile, args.i_start, args.i_end)
#ipy.embed()
num_successes = 0
num_total = 0
failures =[]
for i_task, demo_id_rope_nodes in holdout_items:
redprint("task %s" % i_task)
sim_util.reset_arms_to_side(sim_env)
init_rope_nodes = demo_id_rope_nodes["rope_nodes"][:]
# don't call replace_rope and sim.settle() directly. use time machine interface for deterministic results!
time_machine = sim_util.RopeSimTimeMachine(init_rope_nodes, sim_env)
if args.animation:
sim_env.viewer.Step()
eval_util.save_task_results_init(args.resultfile, i_task, sim_env, init_rope_nodes)
for i_step in range(args.eval.num_steps):
redprint("task %s step %i" % (i_task, i_step))
sim_util.reset_arms_to_side(sim_env)
get_state_fn = lambda sim_env: get_state(sim_env, args.eval)
state = get_state_fn(sim_env)
_, new_cloud_ds, new_rope_nodes, _ = get_state_fn(sim_env)
num_actions_to_try = MAX_ACTIONS_TO_TRY if args.eval.search_until_feasible else 1
eval_stats = eval_util.EvalStats()
try:
agenda, q_values_root = select_best_action(sim_env, state, num_actions_to_try, feature_fn, prune_feature_fn, eval_stats, args.eval.warpingcost)
except:
print 'something weird with segment'
time_machine.set_checkpoint('prechoice_%i'%i_step, sim_env)
for i_choice in range(num_actions_to_try):
if agenda[i_choice][0] == -np.inf: # none of the demonstrations generalize
break
redprint("TRYING %s"%agenda[i_choice][1])
#time_machine.restore_from_checkpoint('prechoice_%i'%i_step, sim_env, sim_util.get_rope_params(args.eval.rope_params))
best_root_action = agenda[i_choice][1]
start_time = time.time()
pre_trans, pre_rots = sim_util.get_rope_transforms(sim_env)
#important ?
#try:
#ipy.embed()
eval_stats.success, eval_stats.feasible, eval_stats.misgrasp, full_trajs = compute_trans_traj(sim_env, get_state_fn, best_root_action, i_step, args.eval, animate=args.animation, interactive=args.interactive)
trans, rots = sim_util.get_rope_transforms(sim_env)
eval_stats.exec_elapsed_time += time.time() - start_time
if eval_stats.feasible: # try next action if TrajOpt cannot find feasible action
eval_stats.found_feasible_action = True
break
else:
redprint('TRYING NEXT ACTION')
#except:
redprint('something wrong in compute trans traj')
if not eval_stats.feasible: # If not feasible, restore_from_checkpoint
time_machine.restore_from_checkpoint('prechoice_%i'%i_step, sim_env, sim_util.get_rope_params(args.eval.rope_params))
print "BEST ACTION:", best_root_action
eval_util.save_task_results_step(args.resultfile, i_task, i_step, sim_env, best_root_action, q_values_root, full_trajs, eval_stats, new_cloud_ds=new_cloud_ds, new_rope_nodes=new_rope_nodes)
if not eval_stats.found_feasible_action:
# Skip to next knot tie if the action is infeasible -- since
# that means all future steps (up to 5) will have infeasible trajectories
break
if is_knot(sim_env.sim.rope.GetControlPoints()):
break;
if is_knot(sim_env.sim.rope.GetControlPoints()):
num_successes += 1
else:
failures.append(i_task)
num_total += 1
redprint('Eval Successes / Total: ' + str(num_successes) + '/' + str(num_total))
print failures
def replay_on_holdout(args, sim_env):
holdoutfile = h5py.File(args.eval.holdoutfile, 'r')
loadresultfile = h5py.File(args.replay.loadresultfile, 'r')
loadresult_items = eval_util.get_holdout_items(loadresultfile, args.tasks, args.taskfile, args.i_start, args.i_end)