-
Notifications
You must be signed in to change notification settings - Fork 35
/
Copy patharc-interface.l
1318 lines (1306 loc) · 65.2 KB
/
arc-interface.l
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
;; -*- mode: lisp;-*-
(require "package://jsk_2015_05_baxter_apc/euslisp/lib/util.l")
(require "package://jsk_2016_01_baxter_apc/euslisp/lib/util.l")
(require "package://jsk_arc2017_baxter/euslisp/lib/baxter-interface.l")
(ros::load-ros-manifest "jsk_arc2017_baxter")
(unless (find-package "JSK_ARC2017_BAXTER")
(make-package "JSK_ARC2017_BAXTER"))
(defclass jsk_arc2017_baxter::arc-interface
:super propertied-object
:slots (attached-objects-
bbox-volume-threshold-
bin-cubes-
bin-movable-regions-
bin-object-volumes-
cardboard-cubes-
finished-objects-
object-boxes-
object-coords-
orders-
postponed-objects-
rack-leg-cubes-
tote-cubes-
tote-movable-regions-
unfinished-objects-
))
(defmethod jsk_arc2017_baxter::arc-interface
(:init ()
;; initialize slots
(setq bbox-volume-threshold- 0.01) ;; [m^3]
(setq attached-objects- (make-hash-table))
(setq bin-cubes- (make-hash-table))
(setq bin-movable-regions- (make-hash-table))
(setq bin-object-volumes- (make-hash-table))
(dolist (bin (list :a :b :c))
(sethash bin bin-object-volumes- 0))
(setq object-boxes- (make-hash-table))
(setq object-coords- (make-hash-table))
(setq cardboard-cubes- (make-hash-table))
(setq tote-cubes- (make-hash-table))
(setq tote-movable-regions- (make-hash-table))
(setq postponed-objects- (make-hash-table))
(setq rack-leg-cubes- (make-hash-table))
(setq finished-objects- (make-hash-table))
(setq unfinished-objects- (make-hash-table)))
(:arc-reset-pose
(&optional (arm :arms) &rest args)
(dolist (tmp-arm (if (eq arm :arms) (list :rarm :larm) (list arm)))
(send *baxter* :arc-reset-pose tmp-arm))
(send* *ri* :angle-vector (send *baxter* :angle-vector) args))
(:fold-pose-back
(&optional (arm :arms) &rest args)
(dolist (tmp-arm (if (eq arm :arms) (list :rarm :larm) (list arm)))
(send *baxter* :fold-pose-back tmp-arm))
(send* *ri* :angle-vector (send *baxter* :angle-vector) args))
(:bbox->cube
(bbox)
(let* ((dims (ros::tf-point->pos (send bbox :dimensions)))
(bx (make-cube (elt dims 0) (elt dims 1) (elt dims 2))))
(send bx :newcoords
(send *ri* :tf-pose->coords
(send bbox :header :frame_id)
(send bbox :pose)))
bx))
(:cube->movable-region
(cube &key (offset (list 0 0 0)))
(let (movable-region vertex-values)
(send cube :worldcoords)
(dotimes (i 3)
(setq vertex-values (mapcar #'(lambda (x) (aref x i)) (send cube :vertices)))
(pushback (list
(+ (apply #'min vertex-values) (elt offset i))
(- (apply #'max vertex-values) (elt offset i)))
movable-region))
movable-region))
(:set-movable-region-for-bin
(&key (offset (list 0 0 0)))
(let (cube)
(progn
(dolist (bin (list :a :b :c))
(setq cube (gethash bin bin-cubes-))
(sethash bin bin-movable-regions-
(send self :cube->movable-region cube :offset offset))))))
(:set-movable-region-for-tote
(arm &key (offset (list 0 0 0)))
(let (cube)
(setq cube (gethash arm tote-cubes-))
(sethash arm tote-movable-regions- (send self :cube->movable-region cube :offset offset))))
(:get-next-target-bin (arm &key (stamp (ros::time-now)))
(when (eq (length orders-) 0)
(ros::ros-error "[:get-next-target-bin] no work-order, try :get-work-orders first")
(return-from :get-next-target-bin nil))
(let (bin-contents target-bins postponed-bins msg)
(setq msg (one-shot-subscribe "/json_saver/output/bin_contents"
jsk_arc2017_common::ContentArray
:timeout 10000
:after-stamp stamp))
(setq bin-contents
(mapcar #'(lambda (content)
(cons (str2symbol (send content :bin))
(send content :items)))
(send msg :contents)))
(ros::ros-debug "[:get-next-target-bin] get bin-contents ~A" bin-contents)
(setq target-bins
(remove-duplicates
(remove nil
(mapcar
#'(lambda (order)
(let ((item (send order :item))
(bin (str2symbol (send order :bin))))
(ros::ros-debug "[:get-next-target-bin] item ~A, bin ~A" item bin)
(when (find item (cdr (assoc bin bin-contents)) :test #'string=)
(unless
(or (find item (gethash bin finished-objects-) :test #'string=)
(find item (gethash bin postponed-objects-) :test #'string=))
bin))))
orders-))))
;; 66% random target
;; 33% select unfinished-objects (never tried to recognize)
(when (< (random 3) 2) (setq target-bins nil))
(ros::ros-debug "[:get-next-target-bin] get target-bins ~A" target-bins)
(when target-bins
(return-from :get-next-target-bin
(elt target-bins (random (length target-bins)))))
(setq postponed-bins
(remove-duplicates
(remove nil
(mapcar
#'(lambda (order)
(let ((item (send order :item))
(bin (str2symbol (send order :bin))))
(ros::ros-debug "[:get-next-target-bin] item ~A, bin ~A" item bin)
(when (find item (cdr (assoc bin bin-contents)) :test #'string=)
(unless
(find item (gethash bin finished-objects-) :test #'string=)
bin))))
orders-))))
(ros::ros-debug "[:get-next-target-bin] get postponed bins ~A" postponed-bins)
(when postponed-bins
(return-from :get-next-target-bin
(elt postponed-bins (random (length postponed-bins)))))
nil))
(:get-work-orders
(arm)
(let (msg)
(setq msg
(one-shot-subscribe
(format nil "/strategic_work_order/~a_hand" (arm2str arm))
jsk_arc2017_common::WorkOrderArray))
(setq orders- (send msg :orders))))
(:get-next-work-order (arm bin)
(when (eq (length orders-) 0)
(ros::ros-error "[:get-next-work-order] There is no order")
(return-from :get-next-work-order nil))
;; return never tried object
(dolist (skipping-objects
(list (append (gethash bin finished-objects-) (gethash bin postponed-objects-))
(gethash bin finished-objects-)))
(dolist (order orders-)
(unless (find (send order :item) skipping-objects :test #'string=)
(return-from :get-next-work-order order))))
nil)
(:get-certain-work-order
(arm bin)
(when (eq (length orders-) 0)
(ros::ros-error "[:get-certain-work-order] There is no order")
(return-from :get-certain-work-order nil))
(when (null bin) (return-from :get-certain-work-order (elt orders- 0)))
(dotimes (i (length orders-))
(when (string= (send (elt orders- i) :bin)
(symbol-string bin))
(return-from :get-certain-work-order (elt orders- i)))))
(:select-work-order-in-bin
(arm bin &key (stamp (ros::time-now)) (timeout 10))
(let ((box-topic (format nil "~a_hand_camera/cluster_indices_decomposer_label/boxes" (arm2str arm)))
(candidates-topic (format nil "/~a_hand_camera/candidates_publisher/output/candidates" (arm2str arm)))
box-msg box-objects box-labels bin-orders
candidates-msg candidate-labels label-names
unfinished-orders)
(setq bin-orders
(remove nil (mapcar
#'(lambda (order)
(when (string= (send order :bin) (symbol-string bin)) order))
orders-)))
(setq label-names
(ros::get-param (format nil "/~a_hand_camera/label_names"
(arm2str arm))))
(ros::subscribe box-topic jsk_recognition_msgs::BoundingBoxArray
#'(lambda (msg)
(let ((st (send msg :header :stamp)))
(when (> (send st :to-sec) (send stamp :to-sec))
(setq box-msg msg)))))
(ros::subscribe candidates-topic jsk_recognition_msgs::LabelArray
#'(lambda (msg)
(let ((st (send msg :header :stamp)))
(when (> (send st :to-sec) (send stamp :to-sec))
(setq candidates-msg msg)))))
(while (and (not (and box-msg candidates-msg))
(> (+ (send stamp :to-sec) timeout)
(send (ros::time-now) :to-sec)))
(unix::usleep (* 50 1000))
(ros::spin-once))
(ros::unsubscribe box-topic)
(ros::unsubscribe candidates-topic)
(when (and box-msg candidates-msg)
(setq box-labels
(remove nil (mapcar
#'(lambda (box)
(let (volume)
(setq volume (* (send box :dimensions :x)
(send box :dimensions :y)
(send box :dimensions :z)))
(when (> volume 0.0)
(send box :label))))
(send box-msg :boxes))))
(setq candidate-labels
(mapcar #'(lambda (label-msg) (send label-msg :id)) (send candidates-msg :labels)))
(setq box-labels
(remove nil (mapcar
#'(lambda (label)
(when (find label candidate-labels) label))
box-labels)))
(unless box-labels (return-from :select-work-order-in-bin nil))
(setq box-objects (mapcar #'(lambda (label) (elt label-names label)) box-labels))
(ros::ros-debug "arm: ~A, box-objects: ~A" (arm2str arm) box-objects)
(dolist (order bin-orders)
(let ((object-name (send order :item)))
(when (and (find object-name box-objects :test #'string=)
(not (find object-name (append (gethash bin finished-objects-)
(gethash bin postponed-objects-))
:test #'string=)))
(return-from :select-work-order-in-bin order))))
(setq unfinished-orders
(remove nil
(mapcar #'(lambda (order)
(let ((object-name (send order :item)))
(when (and (find object-name box-objects :test #'string=)
(not (find object-name
(gethash bin finished-objects-)
:test #'string=)))
order)))
bin-orders)))
(when unfinished-orders
(return-from :select-work-order-in-bin
(elt unfinished-orders (random (length unfinished-orders))))))
nil))
(:check-exist-in-order (obj)
(let (index)
(setq index
(position obj
(mapcar #'(lambda (order) (send order :item)) orders-) :test #'string=))
(if index
(elt orders- index)
nil)))
(:check-bin-exist (bin) (if (gethash bin bin-cubes-) t nil))
(:recognize-bin-boxes
(&key (stamp (ros::time-now)))
(let ((box-topic (format nil "transformable_bin_markers/output/boxes"))
box-msg box-list bin-list)
(setq box-msg (one-shot-subscribe box-topic
jsk_recognition_msgs::BoundingBoxArray
:timeout 10000
:after-stamp stamp))
(if box-msg
(progn
(ros::ros-info "[~a] [:recognize-bin-boxes] recognize bin boxes" (ros::get-name))
(setq box-list (send box-msg :boxes))
(setq bin-list (list :a :b :c))
(dolist (bin bin-list)
(sethash bin bin-cubes- (send self :bbox->cube (car box-list)))
(setq box-list (cdr box-list))))
(ros::ros-fatal "[:recognize-bin-boxes] cannot recognize bin boxes"))))
(:recognize-cardboard-boxes
(&key (stamp (ros::time-now)))
(let ((box-topic (format nil "transformable_cardboard_markers/output/boxes"))
box-msg box-list cardboard-list)
(setq box-msg (one-shot-subscribe box-topic
jsk_recognition_msgs::BoundingBoxArray
:timeout 10000
:after-stamp stamp))
(if box-msg
(progn
(ros::ros-info "[~a] [:recognize-cardboard-boxes] recognize cardboard boxes" (ros::get-name))
(setq box-list (send box-msg :boxes))
(setq cardboard-list (list :a :b :c))
(dolist (cardboard cardboard-list)
(sethash cardboard cardboard-cubes- (send self :bbox->cube (car box-list)))
(setq box-list (cdr box-list))))
(ros::ros-fatal "[:recognize-cardboard-boxes] cannot recognize cardboard boxes"))))
(:recognize-tote-boxes
(&key (stamp (ros::time-now)))
(let ((box-topic (format nil "transformable_tote_markers/output/boxes"))
box-msg box-list)
(setq box-msg (one-shot-subscribe box-topic
jsk_recognition_msgs::BoundingBoxArray
:timeout 10000
:after-stamp stamp))
(if box-msg
(progn
(ros::ros-info "[~a] [:recognize-tote-boxes] recognize tote bbox" (ros::get-name))
(setq box-list (send box-msg :boxes))
(dolist (arm '(:larm :rarm))
(sethash arm tote-cubes- (send self :bbox->cube (pop box-list)))))
(ros::ros-fatal "[:recognize-tote-boxes] cannot recognize tote bbox"))))
(:visualize-bins ()
(ros::ros-warn ":visualize-bins was deprecated. Please use :visualize-boxes.")
(send self :visualize-boxes :box-type :bin))
(:visualize-boxes (&key (box-type :bin))
"Visualize boxes
Arguments
---------
box-type: symbol
:bin, :tote or :cardboard"
(let (boxes box-color box-cubes)
(cond
((eq box-type :bin) (setq box-cubes bin-cubes- box-color :blue))
((eq box-type :tote) (setq box-cubes tote-cubes- box-color :red))
((eq box-type :cardboard) (setq box-cubes cardboard-cubes- box-color :yellow))
(t (ros::ros-error "Unsupported box-type ~a" box-type))
)
(dolist (box-inside (send box-cubes :list-values))
(let ((box-outside (make-cube (+ (x-of-cube box-inside) 30)
(+ (y-of-cube box-inside) 30)
(z-of-cube box-inside)))
(box-model))
(send box-outside :newcoords (send box-inside :copy-worldcoords))
(send box-outside :translate (float-vector 0 0 15) :world)
(setq box-model (body- box-outside box-inside))
(send box-model :set-color box-color 0.5)
(pushback box-model boxes)))
boxes))
(:recognize-target-object
(arm &key (stamp (ros::time-now)) (timeout 10))
(let ((box-topic (format nil "~a_hand_camera/cluster_indices_decomposer_target/boxes" (arm2str arm)))
box-msg
(com-topic (format nil "~a_hand_camera/cluster_indices_decomposer_target/centroid_pose_array"
(arm2str arm)))
com-msg obj-box obj-coords is-recognized)
(when (ros::get-param "~data_collection" nil)
(ros::ros-info-green "Requesting data collection for shelf-bin/tote.")
(let ((res (ros::service-call (format nil "~a_hand_camera/data_collection_server/save_request" (arm2str arm))
(instance std_srvs::TriggerRequest :init))))
(if (send res :success)
(ros::ros-info-green "~a" (send res :message))
(ros::ros-info-red "~a" (send res :message))
)))
(ros::subscribe box-topic jsk_recognition_msgs::BoundingBoxArray
#'(lambda (msg)
(let ((st (send msg :header :stamp)))
(when (> (send st :to-sec) (send stamp :to-sec))
(setq box-msg msg)))))
(ros::subscribe com-topic geometry_msgs::PoseArray
#'(lambda (msg)
(let ((st (send msg :header :stamp)))
(when (> (send st :to-sec) (send stamp :to-sec))
(setq com-msg msg)))))
(while (and (not (and box-msg com-msg))
(> (+ (send stamp :to-sec) timeout) (send (ros::time-now) :to-sec)))
(unix::usleep (* 50 1000))
(ros::spin-once))
(ros::unsubscribe box-topic)
(ros::unsubscribe com-topic)
(cond
((and box-msg com-msg)
(ros::ros-info "[:recognize-target-object] arm: ~a get cpi msg" arm)
(setq obj-box (send box-msg :boxes))
(setq obj-coords
(mapcar #'(lambda (obj-pose)
(send *ri* :tf-pose->coords
(send com-msg :header :frame_id) obj-pose))
(send com-msg :poses)))
(if (and (> (length obj-box) 0) (> (length obj-coords) 0))
(progn
(sethash arm object-boxes- obj-box)
(sethash arm object-coords- obj-coords)
(setq is-recognized (send box-msg :header :stamp)))
(progn
(ros::ros-error "[:recognize-target-object] arm: ~a obj-box length ~a" arm (length obj-box))
(ros::ros-error "[:recognize-target-object] arm: ~a obj-coords length ~a" arm (length obj-coords))
(setq is-recognized nil))))
(t
(ros::ros-error "[:recognize-target-object] arm: ~a failed to get cpi msg" arm)
(setq is-recognized nil)))
is-recognized))
(:get-largest-object-index
(arm bin &key (stamp (ros::time-now)) (n-random nil))
(let ((box-topic (format nil "~a_hand_camera/cluster_indices_decomposer_label/boxes" (arm2str arm)))
box-msg box-labels label-names)
(setq label-names
(ros::get-param (format nil "/~a_hand_camera/label_names"
(arm2str arm))))
(setq box-msg (one-shot-subscribe box-topic
jsk_recognition_msgs::BoundingBoxArray
:timeout 10000
:after-stamp stamp))
(when box-msg
(setq box-labels
(remove nil (mapcar
#'(lambda (box)
(let (volume)
(setq volume (* (send box :dimensions :x)
(send box :dimensions :y)
(send box :dimensions :z)))
(when (> volume 0.0)
(send box :label))))
(send box-msg :boxes))))
(unless box-labels (return-from :get-largest-object-index nil))
(dolist (skipping-objects
(list (append (gethash bin finished-objects-) (gethash bin postponed-objects-))
(gethash bin finished-objects-)))
(let (label-indices target-indices target-index)
(setq label-indices
(remove nil (mapcar
#'(lambda (label-index)
(let ((obj-name (elt label-names label-index)))
(unless (find obj-name skipping-objects :test #'string=)
label-index)))
box-labels)))
(when label-indices
(if n-random
(progn
(setq target-indices (subseq label-indices 0 n-random))
(setq target-index (elt target-indices (random (length target-indices)))))
(setq target-index (car label-indices)))
(return-from :get-largest-object-index target-index)))))
nil))
(:resolve-collision-between-fingers (arm)
(send *ri* :angle-vector-raw
(send *baxter* :slide-gripper arm 120 :relative nil)
1000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pre-pose arm :cylindrical) 1000 :wait nil)
(send *ri* :wait-interpolation)
(unix::sleep 1)
(send *ri* :angle-vector-raw
(send *baxter* :slide-gripper arm 0 :relative nil)
1000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pre-pose arm :opposed) 1000 :wait nil)
(send *ri* :wait-interpolation))
(:pick-object-in-bin
(arm bin &rest args)
(let (pick-result movable-region)
(setq movable-region (gethash bin bin-movable-regions-))
(unless movable-region
(ros::ros-error "[:pick-object-in-bin] No movable region for bin. Call :set-movable-region-for-bin first.")
(return-from :pick-object-in-bin nil))
(setq pick-result (send* self :pick-object-with-movable-region arm movable-region args))
pick-result))
(:pick-object-in-tote
(arm &rest args)
(let (pick-result movable-region)
(setq movable-region (gethash arm tote-movable-regions-))
(unless movable-region
(ros::ros-error "[:pick-object-in-tote] No movable region for tote. Call :set-movable-region-for-tote first.")
(return-from :pick-object-in-tote nil))
(setq pick-result (send* self :pick-object-with-movable-region arm movable-region args))
pick-result))
(:pick-object-with-movable-region
(arm movable-region &key (n-trial 1) (n-trial-same-pos 1)
(do-stop-grasp nil) (grasp-style :suction) (object-index 0))
"Return value: :grasp-succeeded, :grasp-failed or :ik-failed"
(send *ri* :stop-grasp arm :pinch)
(send *ri* :calib-proximity-threshold arm)
(let (pick-result avs obj-pos obj-cube pinch-yaw suction-yaw near-walls)
;; pick largest bounding box when object-index is 0
(setq obj-pos
(send self :get-object-position arm movable-region :object-index object-index))
(setq obj-cube (send self :bbox->cube (elt (gethash arm object-boxes-) object-index)))
(setq near-walls (send self :check-near-walls obj-pos movable-region :range 100))
(if (< (length near-walls) 2)
(cond
((eq (car near-walls) :rear) (setq pinch-yaw 0) (setq suction-yaw 0))
((eq (car near-walls) :front) (setq pinch-yaw 0) (setq suction-yaw pi))
((eq (car near-walls) :right) (setq pinch-yaw -pi/2) (setq suction-yaw pi/2))
((eq (car near-walls) :left) (setq pinch-yaw pi/2) (setq suction-yaw -pi/2))
(t
(if (> (x-of-cube obj-cube) (y-of-cube obj-cube))
(setq pinch-yaw
(+ (if (eq arm :rarm) pi/2 -pi/2)
(caar (send (send obj-cube :worldcoords) :rpy-angle))))
(setq pinch-yaw (caar (send (send obj-cube :worldcoords) :rpy-angle))))
(while (> pinch-yaw pi/2)
(setq pinch-yaw (- pinch-yaw pi)))
(while (< pinch-yaw -pi/2)
(setq pinch-yaw (+ pinch-yaw pi)))))
(cond
((and (member :rear near-walls) (member :right near-walls))
(setq pinch-yaw (/ pi 4)) (setq suction-yaw (/ pi 4)))
((and (member :rear near-walls) (member :left near-walls))
(setq pinch-yaw (/ -pi 4)) (setq suction-yaw (/ -pi 4)))
((and (member :front near-walls) (member :right near-walls))
(setq pinch-yaw (/ (* 3 pi) 4)) (setq suction-yaw (/ (* 3 pi) 4)))
((and (member :front near-walls) (member :left near-walls))
(setq pinch-yaw (/ (* 3 -pi) 4)) (setq suction-yaw (/ (* 3 -pi) 4)))
(t nil)))
(ros::ros-info "[:pick-object-with-movable-region] arm:~a approach to the object" arm)
(ros::ros-info "[:pick-object-with-movable-region] arm:~a obj-pos: ~a" arm obj-pos)
(send *ri* :gripper-servo-on arm)
;; Setup arm for picking
(let (next-avs target-poss)
(send *baxter* :rotate-gripper arm 0 :relative nil)
(send *baxter* :slide-gripper arm 0 :relative nil)
(let ((target-pos (copy-object obj-pos)))
;; movable-region: ((min-of-x max-of-x) (min-of-y max-of-y) (min-of-z max-of-z))
(setf (elt target-pos 2) (+ (cadr (elt movable-region 2)) 100))
(pushback target-pos target-poss) ;; location above of the target object in z axis
;; Go to a little inside of the bin/tote, 300 (30cm) is the z length of bins
;; and smaller than that of tote. TODO: Fix the hard coded offset.
(setf (elt target-pos 2) (+ (car (elt movable-region 2)) 300))
(pushback target-pos target-poss))
(if (eq grasp-style :suction)
;; suction
(progn
(dolist (target-pos target-poss)
(pushback
(send *baxter* :rotate-wrist-ik arm
(make-coords :pos target-pos
:rpy (float-vector (or suction-yaw 0) 0 0))
:move-palm-end nil
:rotation-axis (if (null suction-yaw) :z t))
next-avs)
)
;; Fold fingers to avoid collision to the bin walls
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pre-pose arm :spherical) 1000
:wait nil)
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pose arm :spherical :angle 90) 1000
:wait t))
;; pinch
(progn
(dolist (target-pos target-poss)
(pushback
(send *baxter* :rotate-wrist-ik arm
(make-coords :pos target-pos
:rpy (float-vector pinch-yaw 0 0))
:move-palm-end t
:rotation-axis t)
next-avs))
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pose arm :cylindrical :angle 90) 1000)))
(dolist (av next-avs)
(unless av
(ros::ros-error "[:pick-object-with-movable-region] arm:~a IK before trying grasp fails. Abort picking" arm)
(return-from :pick-object-with-movable-region :ik-failed)))
;; Move whole arm to location above of the target pose
(send *ri* :angle-vector-sequence-raw next-avs
:fast (send *ri* :get-arm-controller arm :head t) 0 :scale 10.0)
(send *ri* :wait-interpolation))
;; Now hand is inside of the bin, so we can use cylindrical
(send *ri* :move-hand arm (send *baxter* :hand-grasp-pre-pose arm :cylindrical) 1000)
;; Picking trials in the bin
(dotimes (i n-trial)
(dotimes (j n-trial-same-pos)
(when (or (null pick-result) (eq pick-result :grasp-failed))
(setq pick-result
(send self :try-to-pick-object arm obj-pos
:offset (float-vector 0 0 (- (* i -30) 30))
:grasp-style grasp-style
:suction-yaw suction-yaw
:pinch-yaw pinch-yaw)))))
(when do-stop-grasp
(unless (eq pick-result :grasp-succeeded)
(send *ri* :stop-grasp arm)
(if (eq grasp-style :pinch)
(send *ri* :stop-grasp arm :pinch))))
(if (eq grasp-style :suction)
(progn
;; Move underactuated fingers to initial pose
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pre-pose arm :opposed) 1000 :wait nil)))
(send *ri* :gripper-servo-on arm)
pick-result))
(:get-object-position
(arm movable-region &key (object-index 0))
(let (obj-box obj-coords obj-pos)
(setq obj-box (elt (gethash arm object-boxes-) object-index))
(setq obj-coords (elt (gethash arm object-coords-) object-index))
(setq obj-pos (send obj-coords :worldpos))
(dolist (i (list 0 1))
(cond ((> (elt (elt movable-region i) 0) (aref obj-pos i))
(ros::ros-error "[:get-object-position] object is out of movable region. ~a > ~a < ~a"
(elt (elt movable-region i) 1)
(elt (send obj-coords :pos) i)
(elt (elt movable-region i) 0))
(setf (aref obj-pos i) (elt (elt movable-region i) 0)))
((> (aref obj-pos i) (elt (elt movable-region i) 1))
(ros::ros-error "[:get-object-position] object is out of movable region. ~a < ~a > ~a"
(elt (elt movable-region i) 1)
(elt (send obj-coords :pos) i)
(elt (elt movable-region i) 0))
(setf (aref obj-pos i) (elt (elt movable-region i) 1)))
(t nil)))
obj-pos))
(:check-near-walls
(obj-pos movable-region &key (range 100))
(let (near-walls)
(when (< (- (aref obj-pos 0) (elt (elt movable-region 0) 0)) range)
(pushback :rear near-walls)
(ros::ros-info-cyan "[:check-near-walls] Object is near rear wall"))
(when (< (- (elt (elt movable-region 0) 1) (aref obj-pos 0)) range)
(pushback :front near-walls)
(ros::ros-info-cyan "[:check-near-walls] Object is near front wall"))
(when (< (- (aref obj-pos 1) (elt (elt movable-region 1) 0)) range)
(pushback :right near-walls)
(ros::ros-info-cyan "[:check-near-walls] Object is near right wall"))
(when (< (- (elt (elt movable-region 1) 1) (aref obj-pos 1)) range)
(pushback :left near-walls)
(ros::ros-info-cyan "[:check-near-walls] Object is near left wall"))
near-walls))
(:try-to-pick-object
(arm obj-pos &key (offset #f(0 0 0)) (grasp-style :suction) suction-yaw
(pinch-yaw (if (eq grasp-style :pinch) 0)))
(if (eq grasp-style :suction)
(send self :try-to-suction-object arm obj-pos suction-yaw :offset offset)
(send self :try-to-pinch-object arm obj-pos pinch-yaw :offset offset)))
(:try-to-suction-object
(arm obj-pos suction-yaw &key (offset #f(0 0 0)))
(send self :try-to-suction-object-with-gripper-v6 arm obj-pos suction-yaw :offset offset))
(:try-to-suction-object-with-gripper-v4
(arm obj-pos &key (offset #f(0 0 0)))
"Return value: :grasp-succeeded or :grasp-failed"
(let (graspingp)
(send *ri* :angle-vector-raw
(send *baxter* arm :inverse-kinematics
(make-coords :pos (v+ obj-pos offset)
:rpy #f(0 0 0))
:use-gripper t
:rotation-axis :z)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation)
;; start the vacuum gripper after approaching to the object
(ros::ros-info "[:try-to-suction-object-with-gripper-v4] arm:~a start vacuum gripper" arm)
(send *ri* :start-grasp arm)
(unix::sleep 1)
(send *ri* :angle-vector-raw
(send *baxter* arm :inverse-kinematics
(make-coords :pos obj-pos
:rpy #f(0 0 0))
:use-gripper t
:rotation-axis :z)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation-until-grasp arm)
(setq graspingp (send *ri* :graspingp arm :suction))
(ros::ros-info "[:try-to-suction-object-with-gripper-v4] arm:~a graspingp: ~a" arm graspingp)
(unless graspingp
(ros::ros-info "[:try-to-suction-object-with-gripper-v4] arm:~a again approach to the object" arm)
(let ((temp-av (send *baxter* :angle-vector)))
;; only if robot can solve IK
(if (send *baxter* arm :move-end-pos #f(0 0 -50) :local)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0))
(send *ri* :wait-interpolation-until-grasp arm)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector temp-av)
3000 (send *ri* :get-arm-controller arm) 0) ;; revert baxter
(send *ri* :wait-interpolation-until-grasp arm)))
;; lift object
(ros::ros-info "[:try-to-suction-object-with-gripper-v4] arm:~a lift the object" arm)
(send *ri* :gripper-servo-off arm)
(send *ri* :angle-vector-raw (send *baxter* arm :move-end-pos #f(0 0 200) :world)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation)
(unix::sleep 1) ;; wait for arm to follow
(setq graspingp (send *ri* :graspingp arm :suction))
(ros::ros-info "[:try-to-suction-object-with-gripper-v4] arm:~a graspingp: ~a" arm graspingp)
(if graspingp :grasp-succeeded :grasp-failed)))
(:try-to-suction-object-with-gripper-v6
(arm obj-pos suction-yaw &key (offset #f(0 0 0)))
"Return value: :grasp-succeeded or :grasp-failed"
(let (graspingp av
(coords-before-approach (send *baxter* arm :end-coords :copy-worldcoords)))
(send coords-before-approach :locate (v+ obj-pos #f(0 0 300)) :world)
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a suction-yaw: ~a" arm suction-yaw)
;; start the vacuum gripper before approaching to the object
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a start vacuum gripper" arm)
(send *ri* :start-grasp arm)
;; suction: prismatic-based approach
(send *baxter* :slide-gripper arm 120 :relative nil)
(send *baxter* arm :inverse-kinematics
(make-coords :pos (v+ obj-pos offset)
:rpy (float-vector (or suction-yaw 0) 0 0))
:use-gripper t
:rotation-axis (if suction-yaw t :z))
(let ((prismatic-angle (send *baxter* arm :gripper-x :joint-angle)))
(send *baxter* :slide-gripper arm 0 :relative nil)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation) ;; move down only the hand palm
(send *baxter* :slide-gripper arm prismatic-angle :relative nil)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0)
;; FIXME: :wait-interpolation-until using :prismatic-loaded sometimes ends too fast,
;; so currently we only check :grasp (suction pressure).
(send *ri* :wait-interpolation-until arm :grasp)
(send *baxter* :slide-gripper arm 120 :relative nil) ;; maximum angle of prismatic joint
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation-until arm :grasp :prismatic-loaded)
)
(setq graspingp (send *ri* :graspingp arm :suction))
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a graspingp: ~a" arm graspingp)
(unless graspingp
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a again approach to the object" arm)
(let ((temp-av (send *baxter* :angle-vector)))
;; only if robot can solve IK
(if (send *baxter* arm :move-end-pos #f(0 0 -100) :local)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0))
(send *ri* :wait-interpolation-until arm :grasp :prismatic-loaded)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector temp-av)
3000 (send *ri* :get-arm-controller arm) 0) ;; revert baxter
(send *ri* :wait-interpolation-until arm :grasp :prismatic-loaded)))
;; Open fingers in bin
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pre-pose arm :spherical) 1000 :wait nil)
(send *baxter* :angle-vector (send *ri* :state :potentio-vector :wait-until-update t))
(send *ri* :angle-vector-raw (send *baxter* :rotate-gripper arm 30 :relative nil)
1000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation)
;; suction: prismatic-based approach
(send *baxter* :slide-gripper arm 0 :relative nil)
(send *baxter* :rotate-gripper arm 0 :relative nil)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0)
;; suction: prismatic-based approach
;; lift object
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a lift the object" arm)
(send *ri* :gripper-servo-off arm)
(let ((tc (send *baxter* arm :end-coords :copy-worldcoords)))
;; overwrite only world-z
(setf (aref (send tc :worldpos) 2) (elt (send coords-before-approach :worldpos) 2))
(send *baxter* arm :inverse-kinematics tc :rotation-axis :z)
)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation)
(setq graspingp (send *ri* :graspingp arm :suction))
(ros::ros-info "[:try-to-suction-object-with-gripper-v6] arm:~a graspingp: ~a" arm graspingp)
(if graspingp :grasp-succeeded :grasp-failed)))
(:try-to-pinch-object
(arm obj-pos pinch-yaw &key (offset #f(0 0 0)))
"Return value: :grasp-succeeded, :grasp-failed or :ik-failed"
(let (av graspingp pre-coords)
(ros::ros-info "[:try-to-pinch-object] arm:~a pinch-yaw: ~a" arm pinch-yaw)
;; Initialize finger
(send *ri* :move-hand arm
(send *baxter* :hand-grasp-pose arm :cylindrical :angle 40) 1000)
;; start the vacuum gripper before approaching to the object
(ros::ros-info "[:try-to-pinch-object] arm:~a start vacuum gripper" arm)
(send *ri* :start-grasp arm)
(setq av
(send *baxter* arm :inverse-kinematics
(make-coords :pos (v+ obj-pos offset)
:rpy (float-vector pinch-yaw 0 0))
:move-palm-end t
:rotation-axis t))
(if (null av)
(setq av
(send *baxter* arm :inverse-kinematics
(make-coords :pos (v+ obj-pos offset)
:rpy (float-vector pinch-yaw 0 0))
:move-palm-end t
:rotation-axis :z)))
(unless av
(ros::ros-error "[:try-to-pinch-object] arm:~a IK to object fails. Abort picking" arm)
(return-from :try-to-pinch-object :ik-failed))
(send *ri* :update-robot-state :wait-until-update t)
(unless (send *ri* :angle-vector-raw av
3000 (send *ri* :get-arm-controller arm) 0 :end-coords-interpolation t)
(send *ri* :angle-vector-raw av 3000 (send *ri* :get-arm-controller arm) 0))
;; Wait until grasp or finger touch
(send *ri* :wait-interpolation-until arm
:grasp :finger-flexion :finger-loaded :prismatic-loaded :finger-proximity)
(setq av
(send *baxter* arm :inverse-kinematics
(make-coords :pos obj-pos
:rpy (float-vector pinch-yaw 0 0))
:move-palm-end t
:rotation-axis t))
(if (null av)
(setq av
(send *baxter* arm :inverse-kinematics
(make-coords :pos obj-pos
:rpy (float-vector pinch-yaw 0 0))
:move-palm-end t
:rotation-axis :z)))
(unless av
(ros::ros-error "[:try-to-pinch-object] arm:~a IK to object fails. Abort picking" arm)
(return-from :try-to-pinch-object :ik-failed))
(send *ri* :angle-vector-raw av 3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation-until arm
:grasp :finger-flexion :finger-loaded :prismatic-loaded :finger-proximity)
(send *baxter* :angle-vector (send *ri* :state :potentio-vector :wait-until-update t))
(send *baxter* arm :move-end-pos #f(0 0 -20) :world)
(send *ri* :angle-vector-raw
(send *baxter* :slide-gripper arm 120 :relative nil)
3000 (send *ri* :get-arm-controller arm) 0)
(send *ri* :wait-interpolation-until arm :grasp :prismatic-loaded)
(send *baxter* :angle-vector (send *ri* :state :potentio-vector :wait-until-update t))
(send *ri* :stop-grasp arm)
(send *ri* :start-grasp arm :pinch)
(send *ri* :start-grasp arm)
(send *baxter* :angle-vector (send *ri* :state :potentio-vector :wait-until-update t))
(setq graspingp (send *ri* :graspingp arm :pinch))
(ros::ros-info "[:try-to-pinch-object] arm:~a graspingp: ~a" arm graspingp)
;; lift object
(ros::ros-info "[:try-to-pinch-object] arm:~a lift the object" arm)
(setq pre-coords (send (send *baxter* arm :end-coords) :copy-worldcoords))
(send pre-coords :translate #f(0 0 200) :world)
(setq av (send *baxter* arm :inverse-kinematics pre-coords :rotation-axis t))
(if (null av)
(setq av
(send *baxter* arm :inverse-kinematics pre-coords :rotation-axis :z)))
(send *ri* :angle-vector-raw av 3000 (send *ri* :get-arm-controller arm :gripper nil) 0)
(send *ri* :wait-interpolation)
;; slide gripper to grasp tightly
(send *baxter* :rotate-gripper arm -90 :relative nil)
(send *baxter* :slide-gripper arm 0 :relative nil)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector)
:fast (send *ri* :get-arm-controller arm) 0 :scale 3.0)
(send *ri* :wait-interpolation)
(send *baxter* :angle-vector (send *ri* :state :potentio-vector :wait-until-update t))
(setq graspingp (send *ri* :graspingp arm :pinch))
(ros::ros-info "[:try-to-pinch-object] arm:~a graspingp: ~a" arm graspingp)
(if graspingp :grasp-succeeded :grasp-failed)))
(:ik->bin-center
(arm bin &key (offset #f(0 0 0)) (rpy #f(0 0 0))
(rotation-axis t) (use-gripper nil) (move-palm-end nil))
(let (bin-cube bin-coords)
(setq bin-cube (gethash bin bin-cubes-))
(setq bin-coords (send bin-cube :copy-worldcoords))
(send bin-coords :translate
(float-vector 0.0 0.0 (/ (z-of-cube bin-cube) 2.0))
:local)
(send bin-coords :translate offset :world)
(send bin-coords :rotate (aref rpy 0) :z)
(send bin-coords :rotate (aref rpy 1) :y)
(send bin-coords :rotate (aref rpy 2) :x)
(send *baxter* arm :inverse-kinematics bin-coords
:rotation-axis rotation-axis
:use-gripper use-gripper
:move-palm-end move-palm-end)))
(:ik->cardboard-center
(arm cardboard &key (offset #f(0 0 0)) (rpy #f(0 0 0))
(rotation-axis t) (use-gripper nil) (move-palm-end nil))
(let (cardboard-cube cardboard-coords)
(setq cardboard-cube (gethash cardboard cardboard-cubes-))
(setq cardboard-coords (send cardboard-cube :copy-worldcoords))
(send cardboard-coords :translate
(float-vector 0.0 0.0 (/ (z-of-cube cardboard-cube) 2.0))
:local)
(send cardboard-coords :translate offset :world)
(send cardboard-coords :rotate (aref rpy 0) :z)
(send cardboard-coords :rotate (aref rpy 1) :y)
(send cardboard-coords :rotate (aref rpy 2) :x)
;; use prismatic joint as much as possible
(let ((jnt (send *baxter* :joint (format nil "~a_gripper_prismatic_joint" (arm2str arm)))))
(send jnt :joint-angle (send jnt :max-angle))
)
(send *baxter* arm :inverse-kinematics cardboard-coords
:rotation-axis nil :use-gripper nil)
(send *baxter* arm :inverse-kinematics cardboard-coords
:rotation-axis rotation-axis
:use-gripper use-gripper
:move-palm-end move-palm-end)))
(:ik->tote-center
(arm &key (offset #f(0 0 0)) (rpy #f(0 0 0))
(rotation-axis t) (use-gripper nil) (move-palm-end nil))
(let (tote-cube tote-coords)
(setq tote-cube (gethash arm tote-cubes-))
(setq tote-coords (send tote-cube :copy-worldcoords))
(send tote-coords :translate
(float-vector 0.0 0.0 (/ (z-of-cube tote-cube) 2.0))
:local)
(send tote-coords :translate offset :world)
(send tote-coords :rotate (aref rpy 0) :z)
(send tote-coords :rotate (aref rpy 1) :y)
(send tote-coords :rotate (aref rpy 2) :x)
(send *baxter* arm :inverse-kinematics tote-coords
:rotation-axis rotation-axis
:use-gripper use-gripper
:move-palm-end move-palm-end)))
(:move-arm-body->bin-overlook-pose
(arm bin &key (gripper-angle 90))
(let (avs offset rpy
(offset-x (if (eq arm :larm) 30 -50))
(offset-y (if (eq arm :larm) 280 -250)))
(setq avs (list (send *baxter* :avoid-shelf-pose arm (if (eq arm :larm) :d :f))))
(send *baxter* :reset-pose arm)
(send *baxter* :rotate-gripper arm gripper-angle :relative nil)
(setq offset (float-vector offset-x offset-y 250))
(setq rpy
(float-vector 0 pi/2 (if (eq arm :larm) pi/2 -pi/2)))
(send self :ik->bin-center arm bin
:offset offset :rpy rpy :use-gripper nil)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector) 3000
(send *ri* :get-arm-controller arm) 0)))
(:move-arm-body->tote-overlook-pose
(arm &key (gripper-angle 90))
(let (avs offset rpy
(offset-x (if (eq arm :larm) 0 -20))
(offset-y (if (eq arm :larm) 390 -320)))
(setq avs (list (send *baxter* :avoid-shelf-pose arm (if (eq arm :larm) :d :f))))
(send *baxter* :reset-pose arm)
(send *baxter* :rotate-gripper arm gripper-angle :relative nil)
(setq offset (float-vector offset-x offset-y 250))
(setq rpy (float-vector 0 pi/2 (if (eq arm :larm) pi/2 -pi/2)))
(pushback
(send self :ik->tote-center arm
:offset offset :rpy rpy :use-gripper nil)
avs)
(send *ri* :angle-vector-raw (send *baxter* :angle-vector) 3000
(send *ri* :get-arm-controller arm) 0)))
(:wait-for-user-input-to-start (arm)
(let (can-start)
(ros::ros-info "[:wait-for-user-input-to-start] wait for user input to start: ~a" arm)
(ros::wait-for-service "/rviz/yes_no_button")
(while
(not can-start)
(setq can-start (send (ros::service-call
"/rviz/yes_no_button" (instance jsk_gui_msgs::YesNoRequest)) :yes)))
(ros::ros-info "[:wait-for-user-input-to-start] received user input: ~a" arm)))
(:set-object-segmentation-candidates (arm candidates)
(let ((req (instance jsk_recognition_msgs::SetLabelsRequest :init)))
(send req :labels candidates)
(ros::service-call
(format nil "/~a_hand_camera/apply_context_to_label_proba/update_candidates"
(arm2str arm))
req)))
(:set-target-location (arm location)
(if (consp location)
(setq location (format nil "~a_~a" (symbol2str (car location)) (symbol-string (cdr location))))
(setq location (symbol2str location)))
(ros::set-dynparam
(format nil "/~a_hand_camera/candidates_publisher" (arm2str arm))
(cons "target_location" location)))
(:set-arm-state-param (arm state)
(ros::set-param (format nil "~a_hand/state" (arm2str arm)) (symbol2str state)))
(:get-bin-contents (bin)
(ros::get-param
(format nil "/bin_contents/~A" (symbol-string bin))))
(:add-workspace-scene
()
(let ((base-name (send (send *baxter* :base_lk) :name))
(dimensions (list '(2500 10 2000) '(2500 10 2000)))
(positions (list (float-vector 500 1200 0) (float-vector 500 -1200 0)))
(names (list "workspace_left" "workspace_right")))
(dotimes (i (length positions))
(let ((cube (apply #'make-cube (elt dimensions i)))
(pos (elt positions i))
(name (elt names i)))
(send cube :locate pos :world)
(send *co* :add-object cube :frame-id base-name
:relative-pose (send cube :copy-worldcoords)
:object-id name)
)
)
))
(:add-bin-scene (bin)
(let ((cube (gethash bin bin-cubes-))
(base-name (send (send *baxter* :base_lk) :name)))
(send *co* :add-object cube :frame-id base-name
:relative-pose (send cube :copy-worldcoords)
:object-id (format nil "bin_~A" (symbol-string bin)))))
(:delete-bin-scene (bin)
(send *co* :delete-object (gethash bin bin-cubes-)))
(:add-shelf-scene ()
(dolist (bin (list :a :b :c))
(send self :add-bin-scene bin)))
(:delete-shelf-scene ()
(dolist (bin (list :a :b :c))
(send self :delete-bin-scene bin)))
(:add-cardboard-scene (cardboard)
(let (cardboard-cube (base-name (send (send *baxter* :base_lk) :name)))
(setq cardboard-cube (gethash cardboard cardboard-cubes-))
(send *co* :add-object cardboard-cube :frame-id base-name
:relative-pose (send cardboard-cube :copy-worldcoords)
:object-id (format nil "cardboard_~A" (symbol-string cardboard)))))
(:delete-cardboard-scene (cardboard)
(let (cardboard-cube)
(setq cardboard-cube (gethash cardboard cardboard-cubes-))
(send *co* :delete-object cardboard-cube)))
(:add-cardboad-rack-leg-scene (side)
(let* ((cardboard-c-cube (gethash :c cardboard-cubes-))
(cardboard-c-coords (send cardboard-c-cube :copy-worldcoords))
(base-name (send (send *baxter* :base_lk) :name))
rack-leg-cube offset)
(setq offset
(float-vector
(elt (send cardboard-c-cube :worldpos) 0)