-
Notifications
You must be signed in to change notification settings - Fork 0
/
semi2024.l
3049 lines (2896 loc) · 97.3 KB
/
semi2024.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
;;
(require :rcb4robots)
(in-package "X")
(defmethod irtviewer
(:view-scale-event
(event)
(if (null previous-cursor-pos)
(setq previous-cursor-pos (event-pos event)))
(let* ((current-pos (event-pos event))
(x (elt current-pos 0))
(y (elt current-pos 1))
(dx (- x (elt previous-cursor-pos 0)))
(dy (- y (elt previous-cursor-pos 1)))
(vtp (v- viewpoint viewtarget))
)
;;(send self :move-viewing-around-viewtarget event x y dx dy viewer)
(send self :viewpoint
(v+ viewpoint
(scale (* 0.01 (if (> (abs dx) (abs dy)) dx dy) (1+ (norm vtp)))
(normalize-vector vtp))))
(send self :look1)
(send self :draw-objects)
(setq previous-cursor-pos current-pos)))
(:view-slide-event
(event)
(if (null previous-cursor-pos)
(setq previous-cursor-pos (event-pos event)))
(let* ((current-pos (event-pos event))
(x (elt current-pos 0))
(y (elt current-pos 1))
(dx (- x (elt previous-cursor-pos 0)))
(dy (- y (elt previous-cursor-pos 1)))
(vtp (v- viewpoint viewtarget))
(v (send viewer :viewing :transform-vector
(scale (* 0.001 (norm vtp))
(float-vector (* -1 dx) dy 0))))
(tp (send self :viewtarget))
(dv (v- v viewpoint)))
(send self :viewpoint v)
(send self :viewtarget (v+ tp dv))
(send self :look1)
(send self :draw-objects)
(setq previous-cursor-pos current-pos)))
(:keyed-move-coords-event
(event)
(let ((state (event-state event)))
;;(print-event event)
(when (memq :left state)
(cond
((memq :shift state)
(send self :view-slide-event event))
((memq :control state)
(send self :view-scale-event event))
(t (send self :move-coords-event event))))
))
(:new-ui
nil
(let ((viewer (send self :viewer)))
(send viewer :viewsurface :set-event-proc
:buttonrelease-left :draw-event self)
(send viewer :viewsurface :set-event-proc
:buttonpress :set-cursor-pos-event self)
(send viewer :viewsurface :set-event-proc
:motionnotify-left :keyed-move-coords-event self)
t)
)
)
(in-package "USER")
(defun free-arms nil
(send *ri* :free :larm-elbow-p :rarm-elbow-p)
)
(defun rest-pose nil
(send *ri* :neutral)
(free-arms)
)
(defun init-pose nil
(send *ri* :hold)
(send *robot* :angle-alist
'((:rarm-shoulder-p -27.405)
(:rarm-shoulder-r -3.07125)
(:rarm-shoulder-y 43.0987)
(:rarm-elbow-p 30.5775)
(:rarm-wrist-p -58.725)
(:rarm-wrist-r -33.3113)
(:rarm-gripper-r 28.8225)
(:rarm-gripper2-r 28.8225)
(:larm-shoulder-p -37.9688)
(:larm-shoulder-r -0.30375)
(:larm-shoulder-y -42.795)
(:larm-elbow-p 67.3988)
(:larm-wrist-p -84.78)
(:larm-wrist-r 8.9775)
(:larm-gripper-r 29.0925)
(:larm-gripper2-r 29.0925)
(:rleg-crotch-y 5.644583e-14)
(:rleg-crotch-r -0.135)
(:lleg-crotch-y 0.135)
(:lleg-crotch-r 0.135)
(:head-neck-y 6.615)
(:head-neck-p 50.3212)))
(send *ri* :angle-vector (send *robot* :angle-vector) 2000)
)
(defclass sample-crank
:super cascaded-link
:slots (handle crank-joint)
)
(defmethod sample-crank
(:init
(&rest args
&key (root-bar-height 150) (handle-base-radius 30) (handle-bar-height 70)
&allow-other-keys)
(send-super* :init args)
(setq handle nil)
;; 1. make links links and assoc all links
(let ((rl (send self :make-root-link root-bar-height))
(cl (send self :make-crank-link handle-base-radius handle-bar-height)))
(send cl :translate (float-vector 0 0 root-bar-height) :world)
;; 2. assoc links
;; Root link should be associated with "self".
(send self :assoc rl)
(send rl :assoc cl)
;; 3. make all joints
;; Before making joints, you should :assoc all links.
(setq crank-joint (instance rotational-joint :init
:parent-link rl :child-link cl
:name :crank-joint :axis :z
:min *-inf* :max *inf*))
;; 4. define slots for robot class
;; links and joint-list for cascaded-link.
(setq links (list rl cl))
(setq joint-list (list crank-joint))
;; 5. call :init-ending after defining links and joint-list and return "self"
(send self :init-ending)
self))
;; Methods to define robot links
(:make-root-link
(root-bar-height)
(instance bodyset-link :init (make-cascoords)
:bodies (list (make-cylinder 5 root-bar-height))
:name :crank-root-link))
(:make-crank-link
(handle-base-radius handle-bar-height)
(let* ((handle-base-thickness 10)
(handle-bar-radius 5)
(handle-base (make-cube (* handle-bar-radius 2) handle-base-radius handle-base-thickness))
(handle-bar (make-cylinder handle-bar-radius handle-bar-height)))
(send handle-bar :translate
(float-vector 0 (- handle-bar-radius handle-base-radius) (/ handle-base-thickness 2.0)))
(send handle-base :translate (float-vector 0 (/ handle-base-radius -2.0) 0))
(send handle-base :assoc handle-bar)
(send handle-base :translate (float-vector 0 0 (/ handle-base-thickness 2.0)))
(let* ((br (instance bodyset-link :init (make-cascoords)
:bodies (list handle-base handle-bar) :name :crank-handle-link))
(ahandle
(make-cascoords :coords
(send (send handle-base :copy-worldcoords)
:translate (float-vector 0 (* -0.5 handle-base-radius) (/ handle-bar-height 2.0)))
:name :crank-handle)))
(send br :assoc ahandle)
(push ahandle handle)
br)))
(:handle () handle)
(:crank-handle () (car handle))
(:crank-joint (&rest args) (forward-message-to crank-joint args))
)
(defclass sample-broom
:super cascaded-link
:slots (handle)
)
(defmethod sample-broom
(:init
(&rest args
&key (sweep-height 50) (sweep-width 26) (sweep-thickness 20)
(bar-length 300) (bar-width 10)
&allow-other-keys)
(send-super* :init args)
(setq handle nil)
;; 1. make links links and assoc all links
(let ((rl (send self :make-broom-link
sweep-height sweep-width sweep-thickness
bar-length bar-width)))
;; 2. assoc links
;; Root link should be associated with "self".
(send self :assoc rl)
;; 3. make all joints
;; Before making joints, you should :assoc all links.
;; 4. define slots for robot class
;; links and joint-list for cascaded-link.
(setq links (list rl))
(setq joint-list nil)
;; 5. call :init-ending after defining links and joint-list and return "self"
(send self :init-ending)
self))
;; Methods to define robot links
(:make-broom-link
(sh ;; sw = Sweep Height
sw ;; sw = Sweep Width
st ;; st = Sweep Thickness
bl ;; bl = Bar Length
bw) ;; bw = Bar Width
(let* ((bar (make-cylinder (/ bw 2.0) bl))
(sweep (make-prism (list (float-vector sw (- sh) 0)
(float-vector (- sw) (- sh) 0)
(float-vector (* -0.5 bw) 0 0)
(float-vector (* 0.5 bw) 0 0))
st)))
(send bar :locate (float-vector 0 0 sh) :world)
(send sweep :rotate pi/2 :x)
(send sweep :locate (float-vector 0 10 sh) :world)
(send bar :set-color :brown)
(send sweep :set-color :red)
(send bar :assoc sweep)
(let ((br (instance bodyset-link :init (make-cascoords)
:bodies (list bar sweep))))
(dolist (rate (list 0.8 0.6))
(push (make-cascoords :pos (float-vector 0 0 (+ (* rate bl) sh))) handle))
(dolist (hc handle) (send br :assoc hc))
br)))
(:handle () handle)
)
(format t " (semi-init) ;; to use :new-ui and show kxrl2l6a6h2m :walk-motion~%")
(defun semi-init nil
(when (not (boundp '*robot*))
(if (probe-file "models/kxrl2l6a6h2m.l")
(load "models/kxrl2l6a6h2m.l")
(make-kxr-robot "kxrl2l6a6h2m"))
(setq *robot* (instance kxrl2l6a6h2m-robot :init))
(objects (list *robot*))
(send *irtviewer* :new-ui)
(send *irtviewer* :draw-objects)
(send *irtviewer* :look-all)
(send *irtviewer* :draw-objects)
(send *robot* :walk-motion)
(send *irtviewer* :look-all)
(send *irtviewer* :draw-objects)
(send *robot* :walk-motion :angle 30 :y 50)
)
)
(defmethod robot-model
(:shake-cocktail
(&key (target-pos (float-vector 120 0 0))
(offset-z 50)
(swing-x 30)
(swing-y 5)
(obj (make-cylinder 15 100)))
(send self :reset-pose)
(send self :newcoords (make-coords))
(setq *obj* obj)
(send obj :set-color (float-vector 1 1 0))
(send self :reset-pose)
(objects (list self obj))
(send self :inverse-kinematics
(list (make-coords :pos target-pos))
:move-target
(list (send self :larm :end-coords))
:link-list
(list (send self :link-list
(send (send self :larm :end-coords) :parent)
(car (send self :larm :links))))
:translation-axis (list t)
:rotation-axis (list nil))
(let* ((cnt 0.0))
(do-until-key
(incf cnt 0.1)
(send self
:inverse-kinematics
(list (make-coords :pos target-pos)
;;:pos (v+ target-pos
;;(float-vector (* swing-x (sin cnt))
;;(* swing-y (cos cnt)) 0)))
#'(lambda ()
(send (send (send self :larm :end-coords) :copy-worldcoords)
:translate (float-vector 0 0 offset-z) :local)))
:move-target
(list (send self :larm :end-coords)
(send self :rarm :end-coords))
:link-list
(list (send self :link-list
(send (send self :larm :end-coords) :parent)
(car (send self :larm :links)))
(send self :link-list
(send (send self :rarm :end-coords) :parent)
(car (send self :rarm :links))))
:translation-axis (list :z t)
:rotation-axis (list nil :z))
(send obj :newcoords (send (send self :larm :end-coords) :copy-worldcoords))
(send *irtviewer* :draw-objects))))
(:crank-motion
()
"crank motion using full body ik"
(send self :reset-pose)
(send self :newcoords (make-coords))
(send self :fix-leg-to-coords (make-coords))
(send self :update-descendants)
(setq *crank* (instance sample-crank :init))
(send *crank* :locate #f(100 70 0) :world)
(objects (list *crank* self))
(let* ((cog-target-pos
(if (some #'null (send self :legs))
(send (car (send self :links)) :worldpos)
(apply #'midpoint 0.5 (send self :legs :end-coords :worldpos))))
(fix-leg-coords
(unless (some #'null (send self :legs))
(send self :legs :end-coords :copy-worldcoords)))
;; append legs' parameters for move-target, link-list, thre, rotation-axis, and target-coords
;; all parameter list -> (list larm rleg lleg)
(move-target (append (list (send self :larm :end-coords))
(send self :legs :end-coords)))
(link-list (mapcar #'(lambda (l) (send self :link-list (send l :parent)))
move-target))
(thre (list 15 1 1))
(rotation-axis (list nil t t))
(fp (apply #'midpoint 0.5 (send-all fix-leg-coords :worldpos))))
(do-until-key
(send *crank* :crank-joint :joint-angle 15 :relative t)
(let* ((target-coords (append (list (send *crank* :crank-handle)) fix-leg-coords)))
(send self :fullbody-inverse-kinematics target-coords
:move-target move-target :link-list link-list
:rotation-axis rotation-axis :thre thre
:look-at-target t :centroid-thre 10.0
:dump-command nil)
;; draw
(send *irtviewer* :draw-objects :flush nil)
(send (send self :support-polygon '(:rleg :lleg)) :draw-on :flush nil :width 4)
(mapcar #'(lambda (act ref)
(send act :draw-on :flush nil :size 100)
(send ref :draw-on :flush nil :color #f(1 0 0)))
(append (list (let ((ac (send self :centroid)))
(setf (elt ac 2) 0) ac))
(send-all move-target :worldpos))
(append (list cog-target-pos) target-coords))
(send self :draw-torque *viewer*)
(send *irtviewer* :flush)
(x::window-main-one)
))
))
(:full-body-ik
(&key (target-pos (float-vector 0 0 400))
(target (make-coords :pos target-pos))
(use-torso t) (use-leg) (debug-view :no-flush))
"full body ik"
(send self :reset-pose)
(if (= (length (car (send self :legs))) 6)
(send self :legs :angle-vector #f(0 0 -10 20 0 -10)))
(if (some #'null (send self :legs))
(send self :newcoords (make-coords))
(send self :fix-leg-to-coords (make-coords) :lleg))
(send self :update-descendants)
(let* ((move-target (send self :larm :end-coords))
(link-list
(send self :link-list
(send move-target :parent)
(cond
(use-leg (send self :lleg :end-coords :parent))
(use-torso (send self :torso :root-link))
(t (send self :larm :root-link))))))
(objects (list self))
(setq *viewer* (send *irtviewer* :viewer))
(do-until-key
(let ((dif-pos (send move-target :difference-position target
:translation-axis t))
(dif-rot (send move-target :difference-rotation target
:rotation-axis nil)))
(send* self :inverse-kinematics-loop dif-pos dif-rot
:link-list link-list
:target-coords target
:move-target (send self :larm :end-coords)
:rotation-axis nil :translation-axis t
:manipulability-gain 0.05
:debug-view debug-view
(if use-leg '(:manipulability-limit 0.5)))
(send self :head :look-at
(send self :larm :end-coords :worldpos))
(if (some #'null (send self :legs))
(send self :newcoords (make-coords))
(send self :fix-leg-to-coords (make-coords) :lleg))
(if use-leg (send *irtviewer* :draw-objects :flush nil))
(send *irtviewer* :viewer :viewsurface :color #f(1 1 1))
(send *irtviewer* :viewer :viewsurface :line-width 2)
(send *irtviewer* :viewer :viewsurface :3d-line
(send self :larm :end-coords :worldpos)
(send self :rarm :end-coords :worldpos))
(send *irtviewer* :flush)
)
))
)
(:dual-arm-ik
nil
(let ((i 0) link-list move-target target-coords)
(send self :reset-pose)
(send self :fix-leg-to-coords (make-coords))
(send self :update-descendants)
;; setup move-target and link-list
(setq move-target (send self :arms :end-coords))
(setq link-list (mapcar #'(lambda (mt) (send self :link-list mt)) (send-all move-target :parent)))
;;
(setq *broom* (instance sample-broom :init))
(send *broom* :locate #f(100 0 0))
(setq *viewer* (send *irtviewer* :viewer))
(send self :head :look-at (apply #'midpoint 0.5 (send-all (send *broom* :handle) :worldpos)))
(objects (list self *broom* (send self :head :end-coords)
(apply #'midcoords 0.5 (send-all (send *broom* :handle) :worldcoords))))
(do-until-key
(send self :inverse-kinematics (send *broom* :handle)
:link-list link-list :move-target move-target
:stop 500 :thre '(10 10)
:rotation-axis '(nil nil) :debug-view nil :dump-command nil)
(send self :head :look-at
(apply #'midpoint 0.5 (send-all (send *broom* :handle) :worldpos))
)
(send *broom* :orient (* 0.2 (sin (/ i 10.0))) :x :world)
(send *broom* :locate (float-vector 100 (* 100 (sin (/ (incf i) 10.0))) 0) :world)
(send *irtviewer* :draw-objects)
(x::window-main-one)
(incf i)
)
))
(:dual-manip-ik
(&key (n 10) (obj (make-cube 20 40 50))
(obj-pos (float-vector 150 0 240))
&rest args)
"dual-armed object manipulation"
(send obj :newcoords (make-coords :pos obj-pos))
(objects (append (list obj self) (send self :head :end-coords)))
(setq *viewer* (send *irtviewer* :viewer))
(send self :reset-pose)
(send self :fix-leg-to-coords (make-coords))
(send self :update-descendants)
(setq *obj* obj)
(dolist (l '(:rarm :larm))
(send obj :put l ;; generate target coords
(make-cascoords
:coords
(send (send (send obj :copy-worldcoords)
:rotate (case l (:rarm pi/2) (:larm -pi/2)) :z)
:translate (float-vector -20 0 0))))
(send obj :assoc (send obj :get l)))
(send obj :set-color :blue)
(send self :head :look-at (send obj :worldpos))
(let ((i 0))
(do-until-key
;; rotate target coords
(when (/= i 0)
(let ((l (cond
((or (= (mod i 4) 1) (= (mod i 4) 2)) :rarm)
((or (= (mod i 4) 3) (= (mod i 4) 0)) :larm)))
(rot (if (oddp (mod i 4)) (* (case (mod i 4) (1 1) (3 -1)) (deg2rad 90))))
(trs (float-vector (* (expt -1 (mod i 2)) 10) 0 0)))
(send obj :dissoc (send obj :get l))
(send obj :assoc (send obj :get l))
(if (oddp (mod i 4))
(send (send obj :get l) :rotate rot :x))
(send (send obj :get l) :translate trs)))
(with-move-target-link-list
(mt robot-ll self '(:rarm :larm))
(let* ((ret
(append-obj-virtual-joint
robot-ll (mapcar #'(lambda (l) (send obj :get l)) '(:rarm :larm))
:joint-class 6dof-joint))
(ll (car ret)) (ot (cadr ret))
(rotation-axis
(cond
((= (mod i 4) 1) '(:x t))
((= (mod i 4) 3) '(t :x))
(t '(t t))))
(weight
(fill (instantiate float-vector
(send self :calc-target-joint-dimension ll))
1.0)))
(dotimes (i 3)
(setf (elt weight (+ (- (send self :calc-target-joint-dimension ll) 6) i)) 0.001))
(send (send (car ot) :parent) :assoc obj)
(send* self :inverse-kinematics ot
:link-list ll :move-target mt
:rotation-axis rotation-axis
:weight weight
:union-link-list
#'(lambda (tmp-ll)
(apply #'append
(mapcar
#'(lambda (f)
(send self :calc-union-link-list
(mapcar #'(lambda (l)
(funcall
f
#'(lambda (x) (member x (send self :links))) l))
tmp-ll)))
(list #'remove-if-not #'remove-if))))
:jacobi #'(lambda (tmp-ll tmp-mt tmp-ta tmp-ra)
(calc-jacobian-from-link-list-including-robot-and-obj-virtual-joint
tmp-ll tmp-mt ot self :rotation-axis tmp-ra))
;;:debug-view t
:debug-view :no-message
:dump-command nil
(append (if (= i 0) '(:stop 100)) args))
(send (send (car ot) :parent) :dissoc obj)
))
(incf i)
(send self :head :look-at (send obj :worldpos))
(when (> i n) (return-from :dual-manip-ik nil))
)
))
(:walk-forward
(&key (step-height 5) (step 25) (n 3) (th 0))
"walking motion using preview-control, gait-generator, and fullbody ik"
(let (footstep-list)
(send self :reset-pose)
(send self :legs :move-end-pos #f(0 0 20))
(send self :fix-leg-to-coords (make-coords))
(dotimes (i n)
(push (make-coords :coords
(send
(send (send self (if (evenp i) :rleg :lleg)
:end-coords :copy-worldcoords)
:rotate (deg2rad th) :z)
:translate (float-vector (* i step) 0 0))
:name (if (evenp i) :rleg :lleg))
footstep-list))
(push
(make-coords :coords
(send (send (send self (if (evenp n) :rleg :lleg)
:end-coords :copy-worldcoords)
:rotate (deg2rad th) :z)
:translate (float-vector (* n step) 0 0))
:name (if (evenp n) :rleg :lleg))
footstep-list)
(push
(make-coords :coords
(send (send (send self (if (evenp n) :lleg :rleg)
:end-coords :copy-worldcoords)
:rotate (deg2rad th) :z)
:translate (float-vector (* n step) 0 0))
:name (if (evenp n) :lleg :rleg))
footstep-list)
(setq footstep-list (reverse footstep-list))
(objects (append (list self) footstep-list))
;; This should have :l/r method or :l/r name.
(setq *viewer* (send *irtviewer* :viewer))
(send self :calc-walk-pattern-from-footstep-list
footstep-list :debug-view :no-message :default-step-height step-height)
(length footstep-list)))
(:walk-motion2 ;; same as :walk-motion in utils.l
(&key (x 100) (y 50) (th 45) (ratio 1.0) (step-height 5))
(send self :reset-pose)
(send self :legs :move-end-pos #f(0 0 20))
(send self :fix-leg-to-coords (make-coords))
(setq *footstep-list*
(send self :go-pos-params->footstep-list x y th))
(objects (cons self *footstep-list*))
(send self :gen-footstep-parameter :ratio ratio)
(setq *viewer* (send *irtviewer* :viewer))
(setq *walk-pattern-list*
(send self :calc-walk-pattern-from-footstep-list
*footstep-list*
:debug-view :no-message :default-step-height step-height))
(length *walk-pattern-list*))
)
;; semi2023 2023.12.29
;;
;; toshima_ws/devel/setup.bash
;; roslaunch rosserial_python eyes_serial_node.launch
;; roslaunch realsense2_camera rs_camera.launch enable_infra1:true enable_infra2:=true
;;
;; Semi2023 2023.9.7
;; Semi2022 2022.5.4
;; Semi2021 2021.10.24
;;
(in-package "IMAGE")
(export '(d405-2d-to-3d))
(setq *d405-scale* (/ 180.0 330.0 220.0))
(defun d405-2d-to-3d (x y d)
(float-vector (* *d405-scale* (- x (/ 848 2)) d)
(* *d405-scale* (- y (/ 480 2)) d)
d))
(defmethod color-image16
(:init (w h &optional img) (send-super :init w h img 16 3))
(:pixel (x y)
(sys:peek entity (+ (* x pixel-bytes) (* y dim1)) :short))
(:set-pixel (x y val)
(sys:poke val entity (+ (* x pixel-bytes) (* y dim1)) :short))
(:3dpos (x y)
(d405-2d-to-3d x y
(send self :pixel (round x) (round y))))
)
(in-package "USER")
;;(require :kxrviewer) ;; when you need GUI
(defmethod x::xwindow
(:left-button (ev)
(setq lpos (x::event-pos ev))
(setq *circle-pos* (float-vector (elt lpos 0) (elt lpos 1)))
(format t ";; *circle-pos* =~A~%" *circle-pos*))
)
(setq *flag* t)
(setq *pos* (float-vector (/ 848 2) (/ 480 2) 0))
(setq *3dpos* (float-vector 0 0 300))
(setq *len* 820)
(setq *wrange* '(50 300))
(setq *drange* '(100 800))
(setq *angle* 0)
(setq *show* t)
(defun sprint (x) (if *show* (print x)))
(defun cbrgb (msg)
(if *flag*
(let (width height)
(setq width (send msg :width) height (send msg :height))
;;(ros::ros-info "w: ~A, h: ~A, encoding: ~A" width height (send msg :encoding))
(setq rgb (instance color-image24 :init width height (send msg :data)))
(if (not (boundp '*v-color*))
(setq *v-color* (instance x::xwindow :create :width width :height height)))
(swap-rgb rgb)
(send *v-color* :putimage (rgb . entity))
(send *v-color* :flush)
)))
(defun cb (msg)
(if *flag*
(let (width height)
(setq width (send msg :width) height (send msg :height))
(setq img (instance color-image16 :init width height (send msg :data)))
(when (not (boundp '*v-gray*))
(setq *v-gray* (instance x::xwindow :create :width width :height height))
(send *v-gray* :set-event-proc :buttonrelease-left :left-button *v-gray*)
)
(when (and (boundp '*pos*) *pos*)
(setq poss (send img :detect-bar *pos* *len* *angle* :val -1 :wrange *wrange*))
)
(setq gray-image (send img :monochromize))
(send *v-gray* :putimage ((send gray-image :to24). entity)) ;; to24 for x::window????
(send *v-gray* :flush)
)))
(defclass target-pos :super propertied-object
:slots (2dpos depth 3dpos scan-angle bar-2dwidth))
(defmethod target-pos
(:init (x y dep)
(setq 2dpos (float-vector x y) depth dep)
(setq 3dpos (image:d405-2d-to-3d x y dep))
self)
(:2dpos nil 2dpos)
(:depth nil depth)
(:3dpos nil 3dpos)
(:scan-angle nil scan-angle)
(:bar-2dwidth nil bar-2dwidth)
)
(defun limage-semishold (li &optional (range '(0 #x10000)))
(let (l ret (min (car range)) (max (cadr range)))
(while li
(setq l (pop li))
(if (< min l max) (push l ret) (push 0 ret)))
(nreverse ret)))
(defun limage-select-blob (li &optional (range '(0 10)))
(let (l (cnt 0) ret (min (car range)) (max (cadr range)))
(while li
(setq l (pop li))
(cond
((> l 0) (incf cnt) (push 0 ret))
((< min cnt max)
(push cnt ret)
(setq cnt 0))
(t (setq cnt 0) (push 0 ret))))
(nreverse ret)))
(defmethod image-2d
(:scan-line-image-2p
(x0 y0 x1 y1 &optional (val 10000))
(cond ((>= x0 (send self :width)) (setq x0 (1- (send self :width))))
((< x0 0) (setq x0 0)))
(cond ((>= x1 (send self :width)) (setq x1 (1- (send self :width))))
((< x1 0) (setq x1 0)))
(cond ((>= y0 (send self :height)) (setq y0 (1- (send self :height))))
((< y0 0) (setq y0 0)))
(cond ((>= y1 (send self :height)) (setq y1 (1- (send self :height))))
((< y1 0) (setq y1 0)))
(setq x0 (round x0) y0 (round y0) x1 (round x1) y1 (round y1))
(let* ((dx (abs (- x1 x0))) (dy (abs (- y1 y0)))
ret err sx sy e2 (flag t))
(declare (type :integer err dx dy sx sy e2))
(if (<= x0 x1) (setq sx 1) (setq sx -1))
(if (<= y0 y1) (setq sy 1) (setq sy -1))
(setq err (- dx dy))
(while flag
(push (send self :pixel x0 y0) ret)
(if (>= val 0) (send self :set-pixel x0 y0 val))
(if (and (= x0 x1) (= y0 y1)) (setq flag nil)
(progn
(setq e2 (* 2 err))
(if (> e2 (- dy))
(setq err (- err dy) x0 (+ x0 sx)))
(if (< e2 dx)
(setq err (+ err dx) y0 (+ y0 sy)))
)))
(reverse ret)
;;(if (> (* sx sy) 0)
;;(reverse ret)
;;(if (> dy dx) ret (reverse ret)))
))
(:detect-bar
(2dp len deg &key (drange *drange*) (wrange *wrange*) (val 10000))
(let* ((xc (elt 2dp 0)) (yc (elt 2dp 1))
(idx 0) (l2 (/ len 2.0)) (rad (deg2rad deg))
x y pidx li0 li (c (* l2 (cos rad))) (s (* l2 (sin rad)))
llen l (x0 (- xc c)) (y0 (- yc s)) (x1 (+ xc c)) (y1 (+ yc s)))
(setq ret nil)
(setq li0 (send self :scan-line-image-2p x0 y0 x1 y1 val))
(setq llen (length li0))
(setq li (limage-semishold li0 drange))
(setq li (limage-select-blob li wrange))
(while li
(setq l (pop li))
(incf idx)
(when
(> l 0)
(setq pidx (- idx (/ l 2.0)))
(setq x (+ x0 (* (- x1 x0) (/ pidx llen))))
(setq y (+ y0 (* (- y1 y0) (/ pidx llen))))
(setq tpos (instance target-pos :init x y (elt li0 (round pidx))))
(setq *3dpos* (send tpos :3dpos))
(setq (tpos . scan-angle) deg)
(setq (tpos . bar-2dwidth) l)
;;(push tpos ret)
(setq ret (list tpos)))
)
ret))
)
;; for kxrmw4 mecanam wheel base
(defun mw-stop nil
(send *robot* :rleg-knee-w :joint-angle 0)
(send *robot* :lleg-knee-w :joint-angle 0)
(send *robot* :rleg-crotch-w :joint-angle 0)
(send *robot* :lleg-crotch-w :joint-angle 0)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector) 100)
)
(defun mw-move-xy (&optional (xv 5) (yv 5) (v 5) &key (scale-trans 1.0) (scale-theta 1.0) (tm 1000))
(send *ri* :hold)
(send *robot* :rleg-crotch-w :joint-angle (+ (* scale-trans (+ xv (- yv))) (* scale-theta v)))
(send *robot* :rleg-knee-w :joint-angle (+ (* scale-trans (+ xv yv)) (* scale-theta v)))
(send *robot* :lleg-crotch-w :joint-angle (+ (* scale-trans (+ xv yv)) (* scale-theta (- v))))
(send *robot* :lleg-knee-w :joint-angle (+ (* scale-trans (+ xv (- yv))) (* scale-theta (- v))))
(send *ri* :wheel-angle-vector (send *robot* :angle-vector) tm)
(mw-stop)
)
(defun mw-fore (&optional (v 10) &key (scale-trans 1.0) (scale-theta 1.0) (tm 1000))
(mw-move-xy v 0 0 :scale-trans scale-trans :scale-theta scale-theta :tm tm)
)
(defun mw-right (&optional (v 10) &key (scale-trans 1.0) (scale-theta 1.0) (tm 1000))
(mw-move-xy 0 v 0 :scale-trans scale-trans :scale-theta scale-theta :tm tm)
)
(defun mw-turn (&optional (v 10) &key (scale-trans 1.0) (scale-theta 1.0) (tm 1000))
(mw-move-xy 0 0 v :scale-trans scale-trans :scale-theta scale-theta :tm tm)
)
;; for kxr2r dual active wheel and dual passive wheel
(defun dw-stop nil
(send *robot* :rleg-crotch-w :joint-angle 0)
(send *robot* :lleg-knee-w :joint-angle 0)
(send *robot* :send-to-ri)
)
(defun dw-fore (&optional (v 10))
(send *robot* :rleg-crotch-w :joint-angle v)
(send *robot* :lleg-knee-w :joint-angle v)
(send *robot* :send-to-ri)
(unix::usleep (* 100 1000))
(dw-stop))
(defun dw-turn (&optional (v 10))
(send *robot* :rleg-crotch-w :joint-angle v)
(send *robot* :lleg-knee-w :joint-angle (- v))
;;(send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector))
(unix::usleep (* 100 1000))
(dw-stop))
;;; for kxrow4 omniwheel base
(defun ow-stop nil
(send *robot* :rleg-knee-w :joint-angle 0)
(send *robot* :lleg-knee-w :joint-angle 0)
(send *robot* :rleg-crotch-w :joint-angle 0)
(send *robot* :lleg-crotch-w :joint-angle 0)
;;(send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :neutral))
)
(defun ow-move (&optional (x 10) (y 0) (th 0) (msec 10))
(send *robot* :rleg-crotch-w :joint-angle (+ x th))
(send *robot* :lleg-crotch-w :joint-angle (- th x))
(send *robot* :rleg-knee-w :joint-angle (+ y th))
(send *robot* :lleg-knee-w :joint-angle (- th y))
;;(send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector))
(unix::usleep (* msec 1000))
(ow-stop)
)
(defun ow-fore (&optional (v 10) (msec 10))
(send *robot* :rleg-crotch-w :joint-angle v)
(send *robot* :lleg-crotch-w :joint-angle (- v))
(send *robot* :rleg-knee-w :joint-angle 0)
(send *robot* :lleg-knee-w :joint-angle 0)
;;(send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector))
(unix::usleep (* msec 1000))
(ow-stop)
)
(defun ow-right (&optional (v 10) (msec 10))
(send *robot* :rleg-crotch-w :joint-angle 0)
(send *robot* :lleg-crotch-w :joint-angle 0)
(send *robot* :rleg-knee-w :joint-angle v)
(send *robot* :lleg-knee-w :joint-angle (- v))
;;(send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector))
(unix::usleep (* msec 1000))
(ow-stop)
)
(defun ow-turn (&optional (v 10) (msec 10))
(send *robot* :rleg-knee-w :joint-angle v)
(send *robot* :lleg-knee-w :joint-angle v)
(send *robot* :rleg-crotch-w :joint-angle v)
(send *robot* :lleg-crotch-w :joint-angle v)
;; (send *robot* :send-to-ri)
(send *ri* :wheel-angle-vector (send *robot* :angle-vector))
(unix::usleep (* msec 1000))
;;(ow-stop)
(send *ri* :wheel-stop)
)
(defvar *semi2022-setup*)
(defun my-robot (&optional name)
(cond
((null name) *my-robot-name*)
((stringp name)
(setq *my-robot-name* name))
((symbolp name)
(setq *my-robot-name* (string-downcase (string name)))))
*my-robot-name*)
(unless (boundp '*my-robot-name*)
(my-robot "kxrl2semi2022"))
(defun kxr-connect nil
(unless (boundp '*ri*)
(make-kxr-robot (my-robot) :viewer nil)
(format *error-output* ";; ~A is created~%" (my-robot))
)
(unless (*ri* . com-port)
(format *error-output* ";; :com-init connect ~A~%"
(if (member :arm *features*)
(send *ri* :com-init :devname "ttyS0")
(send *ri* :com-init)))
(send *ri* :neutral)
)
)
(defun semi-send (&rest args)
(kxr-connect)
(when (*ri* . com-port)
(format t "semi-send ~A~%" args)
(send* *ri* args)
))
(defvar *pose-memory-list*)
(defun save-motion (sym &optional (fname (format nil "~A-motions.l" *my-robot-name*)))
(let* (objs voice-key)
(if (probe-file fname) (setq objs (read-lists fname)))
(setq objs (append objs `((setq ,sym ',(reverse *pose-memory-list*)))))
(apply #'dump-structure fname objs)
sym))
(defun load-motion (&optional (fname (format nil "~A-motions.l" *my-robot-name*)))
(mapcar #'(lambda (l) (eval l) (cadr l)) (read-lists fname)))
(defun run-motion (vlist &optional (time 500))
(dolist (v vlist) (send *ri* :angle-vector v time))
)
;;;
;;; lisp motion
;;;
(defmacro servo (ri poses &optional time)
`(let* ((methods ',poses)
(robo (send ,ri :robot)))
(cond
((symbolp methods)
(send ,ri methods))
(t
(cond
((listp (car methods))
(mapc #'(lambda (method) (send* robo method)) methods))
((find-method robo (car methods))
(send* robo methods))
(t (send* ,ri methods)))
(dolist (j (send robo :joint-list))
(if (eq (send j :joint-type) :wheel) (send j :joint-angle 0)))
(send ,ri :angle-vector (send robo :angle-vector) ,time)))
))
(defun lisp-hold nil (semi-send :hold))
(defun lisp-free nil (semi-send :free))
(defun lisp-hello nil
(semi-send :hold)
(semi-send :neutral)
(semi-send :pose-methods
'((:neutral)
(:angle-plist
:head-neck-p 45 :larm-shoulder-p 30 :rarm-shoulder-p 30
:larm-shoulder-r 10 :rarm-shoulder-r -10)) 300)
(semi-send :pose-methods
'((:angle-plist
:head-neck-p 0 :larm-shoulder-p 0 :rarm-shoulder-p 0)) 300)
)
(defun lisp-right-hand nil
(semi-send :hold)
(semi-send :pose-methods
'((:angle-plist
:rarm-shoulder-p -170 :rarm-elbow-p -20 :rarm-wrist-p 80)) 1000)
)
(defun lisp-left-hand nil
(semi-send :hold)
(semi-send :pose-methods
'((:angle-plist
:larm-shoulder-p -170 :larm-elbow-p -20 :larm-wrist-p 80)) 1000)
)
(defun lisp-both-hand (&optional (time 1500))
(semi-send :hold)
(semi-send :pose-methods
'((:angle-plist
:rarm-shoulder-p -170 :rarm-elbow-p -20 :rarm-wrist-p 80
:larm-shoulder-p -170 :larm-elbow-p -20 :larm-wrist-p 80)) time)
)
(defun lisp-neutral (&optional (time 1500))
(semi-send :hold)
(semi-send :neutral time))
(defun lisp-release nil
(semi-send :release))
(setq *walk-step-time* 500)
(defun lean-right (&key (angle 18) (time *walk-step-time*))
(semi-send :pose-methods `((:lean-right-pose ,angle)) time))
(defun lean-left (&key (angle 18) (time *walk-step-time*))
(semi-send :pose-methods `((:lean-left-pose ,angle)) time))
(defun fore-right (&key (angle 18) (time *walk-step-time*))
(semi-send :pose-methods `((:fore-right-pose ,angle)) time))
(defun fore-left (&key (angle 18) (time *walk-step-time*))
(semi-send :pose-methods `((:fore-left-pose ,angle)) time))
(defun walk-step (&key (step 2) (fore-angle 20) (lean-angle 18)
(time *walk-step-time*))
(while (>= step 1)
(lean-left :angle lean-angle :time time)
(fore-right :angle fore-angle :time time)
(lean-left :angle 0)
(lean-right :angle lean-angle :time time)
(setq step (1- step))
(if (= step 0)
(fore-left :angle 0 :time time)
(fore-left :angle fore-angle :time time))
(lean-right :angle 0 :time time))
)
;;;
;;; Voice Word functions
;;;
(defvar *voice-function-list*)
(defmacro defun-voice (func voice-list &rest body)
;;(unless *semi2022-setup* (semi2022-setup))
`(progn
(if (atom ',voice-list)
(pushnew ,voice-list (get ',func :voice-words))
(setf (get ',func :voice-words)
(remove-duplicates (append ',voice-list (get ',func :voice-words)) :test #'equal)))
(pushnew ',func *voice-function-list*)
(defun ,func (&optional word)
(format *error-output* ";; ~A is called by a word ~A in ~A~%" ',func word
(get ',func :voice-words))
,@body)
',func))