-
Notifications
You must be signed in to change notification settings - Fork 55
/
Copy pathirtrobot.l
1147 lines (1128 loc) · 56.7 KB
/
irtrobot.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
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
;;;
;;; $Id$
;;;
;;; Copyright (c) 1987- JSK, The University of Tokyo. All Rights Reserved.
;;;
;;; This software is a collection of EusLisp code for robot applications,
;;; which has been developed by the JSK Laboratory for the IRT project.
;;; For more information on EusLisp and its application to the robotics,
;;; please refer to the following papers.
;;;
;;; Toshihiro Matsui
;;; Multithread object-oriented language euslisp for parallel and
;;; asynchronous programming in robotics
;;; Workshop on Concurrent Object-based Systems,
;;; IEEE 6th Symposium on Parallel and Distributed Processing, 1994
;;;
;;; Redistribution and use in source and binary forms, with or without
;;; modification, are permitted provided that the following conditions are met:
;;;
;;; * Redistributions of source code must retain the above copyright notice,
;;; this list of conditions and the following disclaimer.
;;; * Redistributions in binary form must reproduce the above copyright notice,
;;; this list of conditions and the following disclaimer in the documentation
;;; and/or other materials provided with the distribution.
;;; * Neither the name of JSK Robotics Laboratory, The University of Tokyo
;;; (JSK) nor the names of its contributors may be used to endorse or promote
;;; products derived from this software without specific prior written
;;; permission.
;;;
;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
;;; THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
;;; PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
;;; CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
;;; EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
;;; PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
;;; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
;;; WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
;;; OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
;;; ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
;;;
(in-package "USER")
(require :irtmodel)
(require :irtdyna)
(defun make-default-robot-link (len radius axis name &optional extbody)
(let (bs b0 b1 c a (r/2 (/ radius 2)))
(setq b0 (make-cylinder r/2 radius))
(setq b1 (make-cube r/2 r/2 len))
(setq c (make-cascoords))
(case axis
(:x (setq a #f(1 0 0)))
(:y (setq a #f(0 1 0)))
(:z (setq a #f(0 0 1)))
(:-x (setq a #f(-1 0 0)))
(:-y (setq a #f(0 -1 0)))
(:-z (setq a #f(0 0 -1)))
(t (setq a axis)))
(if (> (norm (v* a #f(0 0 -1))) 0)
(send c :orient (acos (v. a #f(0 0 -1))) (v* a #f(0 0 -1)) :world))
(send b0 :transform c)
(send b0 :translate (float-vector 0 0 (- r/2)))
(send b1 :translate (float-vector 0 0 (/ len -2)) :locate)
(send b0 :assoc b1)
(send b0 :set-color :red)
(send b1 :set-color :green)
(setq bs (list b0 b1))
(when extbody
(dolist (b extbody) (send b1 :assoc b))
(setq bs (append bs extbody)))
;; set a mass center of default-robot-link as a volume center
(let* ((valid-bodies (remove-if #'(lambda (x)
(and (> (send x :volume) 0) (< (send x :volume) 0))) ;; nan check
bs))
(bodies-centroid
(if (= (length valid-bodies) 1)
(send (car valid-bodies) :centroid)
(scale (/ 1.0 (reduce #'+ (mapcar #'(lambda (x) (send x :volume)) valid-bodies)))
(reduce #'v+ (mapcar #'(lambda (x) (scale (send x :volume) (send x :centroid))) valid-bodies))))))
(instance bodyset-link :init (make-cascoords)
:bodies bs :name name :centroid bodies-centroid)
)))
(defclass robot-model
:super cascaded-link
:slots (larm-end-coords rarm-end-coords
lleg-end-coords rleg-end-coords
head-end-coords torso-end-coords
larm-root-link rarm-root-link
lleg-root-link rleg-root-link
head-root-link torso-root-link
larm-collision-avoidance-links
rarm-collision-avoidance-links
larm rarm lleg rleg torso head
;; sensor slots
force-sensors imu-sensors cameras
;;
support-polygons
))
(defmethod robot-model
(:init-ending
()
(prog1
(send-super :init-ending)
(if (and (not (every #'null (send self :legs))) ;; for legged robot
(not (every #'null (send self :legs :end-coords)))) ;; for robot with legs end-coords
(send self :make-support-polygons))
(setq end-coords-list (remove nil (append end-coords-list
(list larm-end-coords rarm-end-coords
lleg-end-coords rleg-end-coords
head-end-coords torso-end-coords))))
)
)
;; End-coords accessor
(:rarm-end-coords () rarm-end-coords)
(:larm-end-coords () larm-end-coords)
(:rleg-end-coords () rleg-end-coords)
(:lleg-end-coords () lleg-end-coords)
(:head-end-coords () head-end-coords)
(:torso-end-coords () torso-end-coords)
;; Root-link accessor
(:rarm-root-link () rarm-root-link)
(:larm-root-link () larm-root-link)
(:rleg-root-link () rleg-root-link)
(:lleg-root-link () lleg-root-link)
(:head-root-link () head-root-link)
(:torso-root-link () torso-root-link)
(:limb
(limb method &rest args)
(let (ret)
(case method
(:end-coords
(user::forward-message-to
(send self (read-from-string (format nil "~A-END-COORDS" limb)))
args))
(:root-link
(user::forward-message-to
(send self (read-from-string (format nil "~A-ROOT-LINK" limb)))
args))
(:angle-vector
(if args
(progn
(mapcar #'(lambda (l a)
(send l :joint :joint-angle a))
(send self limb) (coerce (car args) cons))
(send self limb :angle-vector))
(coerce (mapcar #'(lambda (l) (send l :joint :joint-angle))
(send self limb)) float-vector)))
(:inverse-kinematics
(let* ((link-list (if (memq :link-list args)
(cadr (memq :link-list args))
(send self :link-list
(send self limb :end-coords :parent)
(send self limb :root-link))))
(collision-avoidance-link-pair
(if (memq :collision-avoidance-link-pair args)
(cadr (memq :collision-avoidance-link-pair args))
(send self :collision-avoidance-link-pair-from-link-list link-list
:collision-avoidance-links (send self limb :collision-avoidance-links)))))
(send* self :inverse-kinematics (car args)
:move-target (if (memq :move-target args)
(cadr (memq :move-target args))
(send self limb :end-coords))
:collision-avoidance-link-pair collision-avoidance-link-pair
:link-list link-list
(cdr args))))
(:move-end
(send* self limb :inverse-kinematics args))
(:move-end-rot
(let ((coords (send self limb :end-coords :copy-worldcoords))
(angle (pop args)) (axis (pop args)) (wrt (pop args)))
(unless wrt (setq wrt :local))
(send* self limb :move-end
(send coords :rotate (deg2rad angle) axis wrt) args)))
(:move-end-pos
(let ((coords (send self limb :end-coords :copy-worldcoords))
(pos (pop args)) (wrt (pop args)))
(unless wrt (setq wrt :local))
(send* self limb :move-end (send coords :translate pos wrt) args)))
(:look-at
(if (send self :head :links) (send* self :inverse-kinematics-loop-for-look-at limb args)))
(:collision-avoidance-links
(user::forward-message-to
(cdr (assoc (intern (format nil "~A-COLLISION-AVOIDANCE-LINKS"
(string-upcase limb))) (send self :slots)))
args))
(:links (send self :limb limb nil))
(:joint-list (send-all (send self :limb limb :links) :joint))
(:gripper (send* self :gripper limb args))
(:joint-order (send self :joint-order limb))
(:cameras (send self :get-sensors-method-by-limb :cameras limb))
(:imu-sensors (send self :get-sensors-method-by-limb :imu-sensors limb))
(:force-sensors (send self :get-sensors-method-by-limb :force-sensors limb))
(t
(cond
((or (null method) (send bodyset-link :method method))
(if method
(send-all (cdr (assoc (intern (string-upcase limb)) (send self :slots))) method)
(cdr (assoc (intern (string-upcase limb)) (send self :slots)))))
(t
(let ((limb-joint-name
(intern (format nil "~A-~A" (string-upcase limb) (string-upcase method)) *keyword-package*)))
(if (find-method self limb-joint-name)
(user::forward-message-to (send self limb-joint-name) args)
(warn ";; error: cannot find method ~A~%" method))
))))
) ;; case method
)) ;; defmethod
(:inverse-kinematics-loop-for-look-at
(limb &rest args)
(let* ((move-target
(if (memq :move-target args)
(cadr (memq :move-target args))
(send self limb :end-coords)))
(link-list (if (memq :link-list args)
(cadr (memq :link-list args))
(send self :link-list
(send move-target :parent)
(send self limb :root-link))))
(stop (if (memq :stop args) (cadr (memq :stop args)) 100))
(warnp (if (memq :warnp args) (cadr (memq :warnp args)) t))
dif-pos dif-rot p-dif-rot (count 0))
(while (and (< (incf count) stop)
(if p-dif-rot (> (norm (v- p-dif-rot dif-rot)) 1e-3) t))
(let* ((target-coords
(orient-coords-to-axis ;; orient target-coords to look-at direction
(make-coords :pos (car args))
(v- (car args) (send move-target :worldpos))))
target-orient move-orient axis-orient axis-orient2 head-weight head-nspace jid)
;; this code assuming that the robot does not have continuous rotation joint for neck-y
(setq p-dif-rot dif-rot
dif-pos (send move-target :difference-position target-coords :translation-axis nil)
dif-rot (send move-target :difference-rotation target-coords :rotation-axis :z))
(setq head-weight (instantiate float-vector (send self :calc-target-joint-dimension link-list))
head-nspace (instantiate float-vector (send self :calc-target-joint-dimension link-list)))
(fill head-weight 1)
(setq target-orient (matrix-column (send target-coords :worldrot) 2)
move-orient (matrix-column (send move-target :worldrot) 2))
(setq jid 0)
(dolist (j (send-all link-list :joint))
(setq axis-orient (send j :parent-link :rotate-vector (case (j . axis) (:x #f(1 0 0)) (:y #f(0 1 0)) (:z #f(0 0 1)) (:-x #f(-1 0 0)) (:-y #f(0 -1 0)) (:-z #f(0 0 -1)) (t (j . axis)))))
;; direciton of non continuous area
(setq axis-orient2 (send j :parent-link :rotate-vector #f(-1 0 0)))
(when (or (and (< (v.* axis-orient move-orient target-orient) 0.0)
(< (v.* axis-orient move-orient axis-orient2) 0.0)
(< (v.* axis-orient axis-orient2 target-orient) 0.0))
(and (> (v.* axis-orient move-orient target-orient) 0.0)
(> (v.* axis-orient move-orient axis-orient2) 0.0)
(> (v.* axis-orient axis-orient2 target-orient) 0.0)))
(if (> (v.* axis-orient move-orient target-orient) 0)
(setf (elt head-nspace jid) -1)
(setf (elt head-nspace jid) 1))
(fill head-weight 0.01)
(setf (elt head-weight jid) 0.0)
(return nil))
(incf jid))
(send self :inverse-kinematics-loop dif-pos dif-rot
:move-target move-target
:collision-avoidance-link-pair nil
:rotation-axis :z
:translation-axis nil
:link-list link-list
:loop count :stop stop ;;:thre nil
:target-coords target-coords ;; for debug-view
:null-space head-nspace
:weight head-weight
:debug-view (cadr (memq :debug-view args))))
)
(if (and p-dif-rot (<= (norm (v- p-dif-rot dif-rot)) 1e-3))
(send self :angle-vector)
(when warnp
(warn ";; :look-at failed.~%")
(warn ";; count : ~a~%" count)
(when p-dif-rot
(warn ";; p-dif-rot : ~a/(~a)~%" p-dif-rot (norm p-dif-rot))
(warn ";; dif-rot : ~a/(~a)~%" dif-rot (norm dif-rot))
(warn ";; diff : ~a < ~A~%" (norm (v- p-dif-rot dif-rot)) 1e-3)
))
nil)
))
(:gripper
(limb &rest args)
(cond
((memq :links args)
(sort (all-child-links (send self limb :end-coords :parent)) #'(lambda (a b) (string< (string (send a :name)) (string (send b :name))))))
((memq :joint-list args)
(send-all (send self :gripper limb :links) :joint))
((memq :angle-vector args)
(if (null (cdr args))
(concatenate
float-vector
(send-all (send self :gripper limb :joint-list) :joint-angle))
(map float-vector #'(lambda (x y) (send x :joint-angle y))
(send self :gripper limb :joint-list) (cadr args))))))
;; sensor accessor definitions
(:camera (sensor-name) "Returns camera with given name" (send self :get-sensor-method :camera sensor-name))
(:force-sensor (sensor-name) "Returns force sensor with given name" (send self :get-sensor-method :force-sensor sensor-name))
(:imu-sensor (sensor-name) "Returns imu sensor of given name" (send self :get-sensor-method :imu-sensor sensor-name))
(:get-sensor-method
(sensor-type sensor-name)
(let ((sens (send self (read-from-string (format nil "~As" sensor-type)))))
(find sensor-name sens :test #'equal :key #'(lambda (x) (send x :name)))))
(:get-sensors-method-by-limb
(sensors-type limb)
(remove-if-not #'(lambda (x) (member (send x :parent) (all-child-links (send self limb :root-link))))
(send self sensors-type)))
;; sensor accessors
(:force-sensors () "Returns force sensors." force-sensors)
(:imu-sensors () "Returns imu sensors." imu-sensors)
(:cameras () "Returns camera sensors." cameras)
;;
(:larm (&rest args)
(unless args (setq args (list nil))) (send* self :limb :larm args))
(:rarm (&rest args)
(unless args (setq args (list nil))) (send* self :limb :rarm args))
(:lleg (&rest args)
(unless args (setq args (list nil))) (send* self :limb :lleg args))
(:rleg (&rest args)
(unless args (setq args (list nil))) (send* self :limb :rleg args))
(:head (&rest args)
(unless args (setq args (list nil))) (send* self :limb :head args))
(:torso (&rest args)
(unless args (setq args (list nil))) (send* self :limb :torso args))
(:arms (&rest args) (list (send* self :larm args) (send* self :rarm args)))
(:legs (&rest args) (list (send* self :lleg args) (send* self :rleg args)))
(:look-at-hand
(l/r)
"look at hand position, l/r supports :rarm, :larm, :arms, and '(:rarm :larm)"
(send self :look-at-target
(mapcar #'(lambda (x) (send self x :end-coords))
(cond
((consp l/r) l/r)
((eq l/r :arms) '(:rarm :larm))
(t (list l/r))))))
;; override inverse-kinematics methods for look-at method
(:inverse-kinematics
(target-coords
&rest args
&key look-at-target
(move-target)
(link-list
(if (atom move-target)
(send self :link-list (send move-target :parent))
(mapcar #'(lambda (mt) (send self :link-list (send mt :parent))) move-target)))
&allow-other-keys)
"solve inverse kinematics, move move-target to target-coords
target-coords and move-target should be given.
link-list is set by default based on move-target -> root link link-list
:look-at-target
~ target head looks at. This task is best-effort and only head joints are used. :look-at-target supports t, nil, float-vector, coords, list of float-vector, list of coords.
other-keys
~ :inverse-kinematics internally calls :inverse-kinematics of cascaded-cords class and args are passed to it. See the explanation of :inverse-kinematics of cascaded-cords class."
(if (or (atom target-coords) (functionp target-coords)) (setq target-coords (list target-coords)))
(when (null (every #'(lambda (x) (or (coordinates-p x) (functionp x))) target-coords))
(warn ";; error: all target-coords should be Coordinates or functions, but get ~A~%" target-coords)
(return-from :inverse-kinematics nil))
(prog1
(send-super* :inverse-kinematics target-coords
:move-target move-target :link-list link-list args)
(send self :look-at-target look-at-target :target-coords target-coords)
))
(:inverse-kinematics-loop
(dif-pos dif-rot
&rest args
&key target-coords debug-view look-at-target
(move-target)
(link-list
(if (atom move-target)
(send self :link-list (send move-target :parent))
(mapcar #'(lambda (mt) (send self :link-list (send mt :parent))) move-target)))
&allow-other-keys)
"move move-target using dif-pos and dif-rot,
look-at-target suppots t, nil, float-vector, coords, list of float-vector, list of coords
link-list is set by default based on move-target -> root link link-list
:inverse-kinematics-loop internally calls :inverse-kinematics-loop function of cascaded-coords class. See the explanation of :inverse-kinematics-loop in cascaded-coords class."
(if (or (atom target-coords) (functionp target-coords)) (setq target-coords (list target-coords)))
(prog1
(send-super* :inverse-kinematics-loop dif-pos dif-rot
:link-list link-list :move-target move-target
:target-coords target-coords args)
(if debug-view (send self :look-at-target look-at-target :target-coords target-coords))
))
;; look-at-target supports -> t, nil, float-vector, coords, list of float-vector, list of coords
(:look-at-target
(look-at-target &key (target-coords))
"move robot head to look at targets, look-at-target support t/nil float-vector coordinates, center of list of float-vector or list of coordinates"
(cond
((float-vector-p look-at-target)
(send self :head :look-at look-at-target))
((coordinates-p look-at-target)
(send self :head :look-at (send look-at-target :worldpos)))
((and (consp look-at-target)
(every #'identity (mapcar #'float-vector-p look-at-target)))
(send self :head :look-at
(scale (/ 1.0 (length look-at-target)) (reduce #'v+ look-at-target :initial-value #f(0 0 0)))))
((and (consp look-at-target)
(every #'identity (mapcar #'coordinates-p look-at-target)))
(send self :head :look-at
(scale (/ 1.0 (length look-at-target)) (reduce #'v+ (send-all look-at-target :worldpos) :initial-value #f(0 0 0)))))
((null look-at-target))
(t (send self :head :look-at (send (car target-coords) :worldpos)))
))
;; init-pose
(:init-pose () "Set robot to initial posture." (send self :angle-vector (instantiate float-vector (send self :calc-target-joint-dimension (cdr (send self :links))))))
(:torque-vector
(&key (force-list) (moment-list) (target-coords)
(debug-view nil)
(calc-statics-p t)
(dt 0.005)
(av (send self :angle-vector))
(root-coords (send (car (send self :links)) :copy-worldcoords))
(calc-torque-buffer-args (send self :calc-torque-buffer-args))
(distribute-total-wrench-to-torque-method (if (and (not (every #'null (send self :legs))) ;; For legged robots
(not (and force-list moment-list target-coords))) ;; If no force-list, moment-list, target-coords are specified
:distribute-total-wrench-to-torque-method-default)))
"Returns torque vector"
(let ((ret-tq
(send self :calc-torque
:debug-view debug-view
:calc-statics-p calc-statics-p
:av av :root-coords root-coords :dt dt
:force-list force-list :moment-list moment-list :target-coords target-coords
:calc-torque-buffer-args calc-torque-buffer-args)))
(when (find-method self distribute-total-wrench-to-torque-method)
(let ((ext-wrench-tq (send self distribute-total-wrench-to-torque-method)))
(dotimes (i (length ret-tq))
(setf (elt ret-tq i) (- (elt ret-tq i) (elt ext-wrench-tq i)))
(send (elt joint-list i) :joint-torque (elt ret-tq i)))))
ret-tq
))
(:distribute-total-wrench-to-torque-method-default
()
;; set default force & moment by solving mimimum internal forces
(let ((target-coords))
(dolist (limb '(:rleg :lleg))
(if (send self limb)
(push (send self limb :end-coords) target-coords)))
(let* ((ret-fm (send self :calc-contact-wrenches-from-total-wrench (send-all target-coords :worldpos)
:total-wrench (concatenate float-vector (send (car (send self :links)) :force) (send (car (send self :links)) :moment)))))
(send self :calc-torque-from-ext-wrenches :force-list (car ret-fm) :moment-list (cadr ret-fm) :target-coords target-coords)
)))
(:calc-force-from-joint-torque
(limb all-torque &key (move-target (send self limb :end-coords)) (use-torso))
"Calculates end-effector force and moment from joint torques."
(let* ((link-list
(send self :link-list
(send move-target :parent)
(unless use-torso (car (send self limb :links)))))
(jacobian
(send self :calc-jacobian-from-link-list
link-list
:move-target move-target
:rotation-axis (list t)
:translation-axis (list t)))
(torque (instantiate float-vector (length link-list))))
(dotimes (i (length link-list))
(setf (elt torque i)
(elt all-torque (position (send (elt link-list i) :joint) (send self :joint-list)))))
(transform (send self :calc-inverse-jacobian (transpose jacobian))
torque)))
(:fullbody-inverse-kinematics
(target-coords
&rest args
&key (move-target) (link-list)
;; default robot root-link 6dof parameters : min, max, root-link-virtual-joint-weight, and weight
(min (float-vector -500 -500 -500 -20 -20 -10))
(max (float-vector 500 500 25 20 20 10))
(root-link-virtual-joint-weight #f(0.1 0.1 0.1 0.1 0.5 0.5))
;; default cog-jacobian parameters : target-centroid-pos, cog-gain, and centroid-thre
(target-centroid-pos (apply #'midpoint 0.5 (send self :legs :end-coords :worldpos))) ;; <- target centroid position.
(cog-gain 1.0) ;; <- cog gain for null-space calculation. cog-gain should be over zero.
(cog-translation-axis :z) ;; translation-axis of cog
(centroid-offset-func nil) ;; offset function for cog
(centroid-thre 5.0) ;; cog convergence threshould [mm]
(additional-weight-list)
(joint-args nil)
(cog-null-space nil)
(min-loop 2) ;; 2 is minimum loop count
&allow-other-keys)
"fullbody inverse kinematics for legged robot.
necessary args : target-coords, move-target, and link-list must include legs' (or leg's) parameters
ex. (send *robot* :fullbody-inverse-kinematics (list rarm-tc rleg-tc lleg-tc) :move-target (list rarm-mt rleg-mt lleg-mt) :link-list (list rarm-ll rleg-ll lleg-ll))
:min
~ lower position limit of root link virtual joint (x y z roll pitch yaw). Default is #f(-500[mm] -500[mm] -500[mm] -20[deg] -20[deg] -10[deg]).
:max
~ upper position limit of root link virtual joint (x y z roll pitch yaw). Default is #f(500[mm] 500[mm] 25[mm] 20[deg] 20[deg] 10[deg]).
:root-link-virtual-joint-weight
~ float-vector of inverse weight of velocity of root link virtual joint or a function which returns the float-vector (x y z roll pitch yaw). This works in the same way as :additional-weight-list in cascaded-coords::inverse-kinematics. Default is #f(0.1 0.1 0.1 0.1 0.5 0.5).
:joint-args
~ list of other arguments passed to :init function of root link virtual joint (6dof-joint class).
~~ :max-joint-velocity
~~~ limit of velocity of root link virtual joint (x y z roll pitch yaw). Default is #f((/ 0.08 0.05)[m/s] (/ 0.08 0.05)[m/s] (/ 0.08 0.05)[m/s] (/ pi 4)[rad/s] (/ pi 4)[rad/s] (/ pi 4)[rad/s]))
other-keys
~ :fullbody-inverse-kinematics internally calls :inverse-kinematics and args are passed to it. See the explanation of :inverse-kinematics.
"
(with-append-root-joint ;; inverse-kinematics with root-link
(link-list-with-robot-6dof self link-list
:joint-class 6dof-joint
:joint-args (append (list :min min :max max) joint-args))
(send* self :inverse-kinematics target-coords
:move-target move-target :link-list link-list-with-robot-6dof
:cog-gain cog-gain :centroid-thre centroid-thre :target-centroid-pos target-centroid-pos
:cog-translation-axis cog-translation-axis :centroid-offset-func centroid-offset-func :cog-null-space cog-null-space
:min-loop min-loop
:additional-weight-list
(append
additional-weight-list
(list (list (car (send self :links)) root-link-virtual-joint-weight)))
args)
))
(:joint-angle-limit-nspace-for-6dof
(&key (avoid-nspace-gain 0.01) (limbs '(:rleg :lleg)))
(let* ((ll (mapcar #'(lambda (l) (send self l :links)) limbs))
(J (send self :calc-jacobian-from-link-list
(mapcar #'(lambda (l) (append (list (car (send self :links))) l)) ll)
:move-target (mapcar #'(lambda (l) (send self l :end-coords)) limbs)
:translation-axis (make-list (length limbs) :initial-element t)
:rotation-axis (make-list (length limbs) :initial-element t)))
(Jb (make-matrix (array-dimension J 0) 6))
(Jj (make-matrix (array-dimension J 0) (send self :calc-target-joint-dimension ll))))
(dotimes (i (array-dimension Jb 0))
(dotimes (ii (array-dimension Jb 1))
(setf (aref Jb i ii) (aref J i ii))))
(dotimes (i (array-dimension Jj 0))
(dotimes (ii (array-dimension Jj 1))
(setf (aref Jj i ii) (aref J i (+ 6 ii)))))
(let ((dthb
(transform (m* (send self :calc-inverse-jacobian Jb) Jj)
(scale (* -1 avoid-nspace-gain)
(joint-angle-limit-nspace
(send-all (send self :calc-union-link-list ll) :joint))))))
(setf (elt dthb 0) 0)
(setf (elt dthb 1) 0)
dthb
)))
(:joint-order
(limb &optional jname-list)
(let ((joint-list (mapcar #'(lambda (x) (cons x (find-if #'(lambda (y) (eq y (send self x))) (send self limb :joint-list)))) (mapcan #'(lambda (x) (if (substringp (format nil "~A-" (symbol-name limb)) (string x)) (list x)))(send self :methods))))
j (result) name)
(unless jname-list
(setq jname-list
(case limb
((:larm :rarm) '("collar" "shoulder" "elbow" "wrist"))
((:lleg :rleg) '("crotch" "knee" "ankle"))
((:torso) '("chest" "weist"))
((:head) '("neck" "head")))))
(dolist (jname jname-list) ;; look for joint corresponds to jname
(while (substringp (string-upcase jname) (setq name (symbol-name (caar joint-list))))
(push
(read-from-string
(format nil ":~A" (subseq name (1- (length name)))))
j)
(pop joint-list))
(nreverse j)
(push j result)
(setq j nil))
(nreverse result)))
(:print-vector-for-robot-limb
(vec)
"Print angle vector with limb alingment and limb indent.
For example, if robot is rarm, larm, and torso, print result is:
#f(
rarm-j0 ... rarm-jN
larm-j0 ... larm-jN
torso-j0 ... torso-jN
)"
(let ((tmp-limbs
(remove-duplicates
(mapcar #'(lambda (l)
(find-if #'(lambda (tmp-limb) (member l (send self tmp-limb :links))) '(:rarm :larm :rleg :lleg :torso :head)))
(send-all (send self :joint-list) :child-link))))
(ordered-joint-list (send self :joint-list)))
(format t " #f(~% ")
(dolist (tmp-limb tmp-limbs)
(dolist (j (send self tmp-limb :joint-list))
(format t "~6,2f " (elt vec (position j ordered-joint-list))))
(format t "~% "))
(format t ")~%")
vec))
(:calc-zmp-from-forces-moments
(forces moments ;; [N] [Nm], sensor local force & moment
&key (wrt :world)
;; :wrt is :local => calc local zmp for robot's root-link coords
;; :wrt is :world => calc world zmp for robot
(limbs
(if (send self :force-sensors)
(remove nil (mapcar #'(lambda (fs)
(find-if #'(lambda (l) (equal fs (car (send self l :force-sensors)))) '(:rleg :lleg)))
(send self :force-sensors)))
'(:rleg :lleg)))
(force-sensors (mapcar #'(lambda (l) (car (send self l :force-sensors))) limbs))
(cop-coords (mapcar #'(lambda (l) (send self l :end-coords)) limbs))
(fz-thre 1e-3) ;; [N]
(limb-cop-fz-list
(mapcar #'(lambda (fs f m cc)
(let ((fsp (scale 1e-3 (send fs :worldpos))) ;; [mm]->[m]
(nf (send fs :rotate-vector f))
(nm (send fs :rotate-vector m)))
(send self :calc-cop-from-force-moment
nf nm fs cc :fz-thre fz-thre :return-all-values t)))
force-sensors forces moments cop-coords)))
"Calculate zmp[mm] from sensor local forces and moments
If force_z is large, zmp can be defined and returns 3D zmp.
Otherwise, zmp cannot be defined and returns nil."
(let* ((limb-cop-fz-list2 (remove nil limb-cop-fz-list))
(limb-fz (reduce #'+ (mapcar #'(lambda (x) (cadr (memq :fz x))) limb-cop-fz-list2) :initial-value 0)))
(if (< limb-fz fz-thre)
nil
(let ((tmpzmp (scale (/ 1.0 limb-fz) (reduce #'v+ (mapcar #'(lambda (x) (scale (cadr (memq :fz x)) (cadr (memq :cop x)))) limb-cop-fz-list2)))))
(cond
((eq wrt :world) tmpzmp)
((eq wrt :local) (send (car (send self :links)) :inverse-transform-vector tmpzmp))
(t )
)))
))
)
;;; moved from rbrarin libraries
(defmethod robot-model
(:foot-midcoords
(&optional (mid 0.5))
"Calculate midcoords of :rleg and :lleg end-coords.
In the following codes, leged robot is assumed."
(apply #'midcoords mid (send self :legs :end-coords))
)
(:fix-leg-to-coords
(fix-coords &optional (l/r :both) &key (mid 0.5) &allow-other-keys) ;; support-leg
"Fix robot's legs to a coords
In the following codes, leged robot is assumed."
(unless (not (some #'null (send self :legs :links)))
(return-from :fix-leg-to-coords nil))
(let (support-coords tmp-coords move-coords pos rot ra)
(cond
((or (eq l/r :left) (eq l/r :lleg))
(setq support-coords
(send self :lleg :end-coords :copy-worldcoords)))
((or (eq l/r :right) (eq l/r :rleg))
(setq support-coords
(send self :rleg :end-coords :copy-worldcoords)))
(t
(setq support-coords
(midcoords mid
(send self :lleg :end-coords :copy-worldcoords)
(send self :rleg :end-coords :copy-worldcoords)))))
(setq tmp-coords (send fix-coords :copy-worldcoords))
(setq move-coords (send support-coords :transformation self))
(send tmp-coords :transform move-coords :local)
(send self :newcoords tmp-coords)
(send self :worldcoords)
tmp-coords))
(:move-centroid-on-foot
(leg fix-limbs
&rest args
&key (thre (mapcar #'(lambda (x) (if (memq x '(:rleg :lleg)) 1 5)) fix-limbs))
(rthre (mapcar #'(lambda (x) (deg2rad (if (memq x '(:rleg :lleg)) 1 5))) fix-limbs))
(mid 0.5)
(target-centroid-pos
(if (eq leg :both)
(apply
#'midpoint mid
(mapcar
#'(lambda (tmp-leg)
(send self tmp-leg :end-coords :worldpos))
(remove-if-not #'(lambda (x) (memq x '(:rleg :lleg))) fix-limbs)))
(send self leg :end-coords :worldpos)))
(fix-limbs-target-coords
(mapcar #'(lambda (x) (send self x :end-coords :copy-worldcoords)) fix-limbs))
(root-link-virtual-joint-weight #f(0.1 0.1 0.0 0.0 0.0 0.5)) ;; use only translation x, y and rotation z
&allow-other-keys)
"Move robot COG to change centroid-on-foot location,
leg : legs for target of robot's centroid, which should be :both, :rleg, and :lleg.
fix-limbs : limb names which are fixed in this IK."
(with-move-target-link-list
(mt ll self fix-limbs)
(let* ()
(send* self :fullbody-inverse-kinematics
fix-limbs-target-coords
:move-target mt :link-list ll
:fix-limbs (remove-if-not #'(lambda (x) (memq x '(:rleg :lleg))) fix-limbs)
:root-link-virtual-joint-weight root-link-virtual-joint-weight
:thre thre :rthre rthre
:target-centroid-pos target-centroid-pos
args)
)))
(:calc-walk-pattern-from-footstep-list
(footstep-list
&key (default-step-height 50) (dt 0.1) (default-step-time 1.0)
(solve-angle-vector-args) (debug-view nil)
((:all-limbs al)
(if (send self :force-sensors)
(remove nil (mapcar #'(lambda (fs)
(find-if #'(lambda (l) (equal fs (car (send self l :force-sensors)))) '(:rleg :lleg)))
(send self :force-sensors)))
'(:rleg :lleg)))
((:default-zmp-offsets dzo)
(mapcan #'(lambda (x) (list x (float-vector 0 0 0))) al)) ;; [mm]
(init-pose-function #'(lambda () (send self :move-centroid-on-foot :both '(:rleg :lleg))))
(start-with-double-support t)
(end-with-double-support t)
(ik-thre 1) (ik-rthre (deg2rad 1))
(q 1.0) (r 1e-6) ;; Q is weighting of output error and R is weighting of input.
(calc-zmp t))
"Calculate walking pattern from foot step list and return pattern list as a list of angle-vector, root-coords, time, and so on.
footstep-list should be given.
:footstep-list
~ (list footstep1 footstep2 ...). :footstep-list can be any length. Each footstep indicates the destinations of swing legs in each step.
~ footstep should be list of coordinate whose :name is identical with one swing leg and whose coords is the destination of that leg. If number of swing legs in a step is one, the footstep can be a coordinate.
~ footstep1 is only for intialization and not executed.
:default-step-height
~ Height of swing leg cycloid trajectories. Default is 50[mm].
:dt
~ Sampling time of preview control and output walk pattern. Default is 0.1[s].
:default-step-time
~ Reference time of each step. The first 10 percent and the last 10 percent of default-step-time is double support phase. Default is 1.0[s].
:solve-angle-vector-args
~ :move-centroid-on-foot is used to solve IK in :calc-walk-pattern-from-footstep-list. :solve-angle-vector-args is passed to :move-centroid-on-foot in the form of (send* self :move-centroid-on-foot ... solve-angle-vector-args). Default is nil.
:debug-view
~ Set t to show visualization. Default is nil.
:all-limbs
~ list of limb names. In each walking step, limbs in :all-limbs but not assigned as swing legs by :footstep-list are considered to be support legs. Default is '(:rleg :lleg) sorted in force-sensors order.
:default-zmp-offsets
~ (list limbname1 offset1 limbname2 offset2 ...). :default-zmp-offsets should include every limb in :all-limbs. offset is a float-vector[mm] and local offset of reference zmp position from end-coords. Default offset is #F(0 0 0)[mm].
:init-pose-function
~ A function which initialize robot's pose. Walking pattern is generated from this initial pose. :init-pose-function is called once at the start of walking pattern generation in the form of (funcall init-pose-function). Default is #'(lambda () (send self :move-centroid-on-foot :both '(:rleg :lleg))).
:start-with-double-support
~ At the start of walking pattern generation, the initial position of reference zmp is
~~ t: midpoint of all-limbs.
~~ nil: midpoint of swing legs of footstep1.
~ Default is t.
:end-with-double-support
~ At the end of walking pattern generation, the final position of reference zmp is
~~ t: midpoint of all-limbs.
~~ nil: midpoint of support legs of the last footstep.
~ Default is t.
:ik-thre
~ Threshold for position error to terminate IK iteration. Default is 1[mm].
:ik-rthre
~ Threshold for rotation error to terminate IK iteration. Default is (deg2rad 1)[rad].
:q
~ Weight Q of the cost function of preview control. Default is 1.0.
:r
~ Weight R of the cost function of preview control. Default is 1e-6.
:calc-zmp
~ Set t to calculate resultant ZMP after IK. The calculated ZMP is visualized if :debug-view is t, and stored as czmp in return value. Default is t.
"
(let* ((res) (ret) (tm 0)
(gg (instance gait-generator :init self dt)))
(funcall init-pose-function)
;; initial move centroid on foot
(send gg :initialize-gait-parameter
footstep-list default-step-time (send self :centroid)
:default-step-height default-step-height :default-double-support-ratio 0.2
:default-zmp-offsets dzo :all-limbs al
:thre ik-thre :rthre ik-rthre
:start-with-double-support start-with-double-support :end-with-double-support end-with-double-support
:q q :r r)
(while (null (setq ret (send gg :proc-one-tick :type :cycloid :debug t :solve-angle-vector-args solve-angle-vector-args))))
(if calc-zmp (dotimes (i 2) (send self :calc-zmp))) ;; for zmp initialization
;; following are in control loop
(while (setq ret (send gg :proc-one-tick :type :cycloid :debug t :solve-angle-vector-args solve-angle-vector-args))
;; only for debug view
(let ((czmp (if calc-zmp
(send self :calc-zmp
(send self :angle-vector)
(send (car (send self :links)) :copy-worldcoords)
:dt dt :pZMPz (elt (elt ret 5) 2))))
(end-coords-list (mapcar #'(lambda (x) (send self x :end-coords :copy-worldcoords)) (gg . all-limbs)))
(contact-state (elt ret 8))
)
(when debug-view
(send self :draw-gg-debug-view
end-coords-list
contact-state
(elt ret 5) ;; rz
(elt ret 6) ;; cog
(elt ret 7) ;; pz
czmp dt)
(x::window-main-one))
(push
(list :angle-vector (car ret)
:root-coords (cadr ret)
:czmp czmp :zmp (elt ret 5) :cog (elt ret 6)
:time tm
:pz (elt ret 7)
:all-limbs al
:contact-state contact-state
:end-coords-list end-coords-list
)
res)
(setq tm (+ tm dt))
))
(reverse res)
))
(:draw-gg-debug-view
(end-coords-list contact-state rz cog pz czmp dt)
(send *viewer* :draw-objects :flush nil)
(labels ((with-modify-color
(col func)
(let ((pc (send *viewer* :viewsurface :color)))
(send *viewer* :viewsurface :color col)
(funcall func)
(send *viewer* :viewsurface :color pc))))
(mapcar #'(lambda (ec cs)
(send ec :draw-on :flush nil :size 300 :color
(if (eq :swing cs) #f(0 1 0) #f(1 0 0))))
end-coords-list contact-state)
(send rz :draw-on :flush nil :size 300 :color #f(0 0 1))
(if czmp (send czmp :draw-on :flush nil :size 200 :width 5))
(with-modify-color
#f(1 0 0)
#'(lambda () (send *viewer* :viewsurface :string 20 20 "red = support leg")))
(with-modify-color
#f(0 1 0)
#'(lambda () (send *viewer* :viewsurface :string 20 50 "green = swing leg")))
(with-modify-color
#f(0 0 1)
#'(lambda () (send *viewer* :viewsurface :string 20 80 "blue = refzmp")))
(with-modify-color
#f(1 1 1)
#'(lambda () (send *viewer* :viewsurface :string 20 110 "white = calc zmp"))))
(send *viewer* :viewsurface :flush)
)
;; generate footstep parameter
;; currently only default, forward and outside
(:gen-footstep-parameter
(&key (ratio 1.0))
"Generate footstep parameter"
(warn ";; generating footstep-parameter...~%")
(let ((pav (send self :angle-vector))
(pc (send self :copy-worldcoords)))
(send self :reset-pose)
(send self :fix-leg-to-coords (make-coords) '(:rleg :lleg))
(let ((dol (abs (elt (apply #'v- (send self :legs :end-coords :worldpos)) 1))))
(labels ((ik-test
(target-coords-func diff-func &optional (limit-func))
(send self :reset-pose)
(send self :fix-leg-to-coords (make-coords) '(:rleg :lleg))
(let* ((tc (send self :rleg :end-coords :copy-worldcoords))
(init-tc (send tc :copy-worldcoords)))
(while (and
(send self :inverse-kinematics
(funcall target-coords-func tc)
:link-list (send self :link-list (send self :rleg :end-coords :parent))
:move-target (send self :rleg :end-coords) :warnp nil)
(if limit-func (funcall limit-func tc init-tc) t)
))
(funcall diff-func tc init-tc))))
(let ((fol (ik-test #'(lambda (tc) (send tc :translate #f(10 0 0)))
#'(lambda (tc init-tc) (abs (elt (v- (send tc :worldpos) (send init-tc :worldpos)) 0)))))
(ool (ik-test #'(lambda (tc) (send tc :translate #f(0 -10 0)))
#'(lambda (tc init-tc) (abs (elt (v- (send tc :worldpos) (send init-tc :worldpos)) 1)))))
(frr (ik-test #'(lambda (tc) (send tc :rotate (deg2rad -2.5) :z))
#'(lambda (tc init-tc) (abs (rad2deg (- (caar (send tc :rpy-angle)) (caar (send init-tc :rpy-angle))))))
#'(lambda (tc init-tc) (> 90 (abs (rad2deg (- (caar (send tc :rpy-angle)) (caar (send init-tc :rpy-angle)))))))
)))
(send self :newcoords pc)
(send self :angle-vector pav)
(warn ";; generating footstep-parameter... done.~%")
(send self :put :footstep-parameter
(list :default-half-offset (float-vector 0 (* 0.5 dol) 0)
:forward-offset-length (* fol 0.5 ratio)
:outside-offset-length (* ool 0.5 ratio)
:rotate-rad (deg2rad (* frr 0.5 ratio))))
)))
))
(:footstep-parameter
()
(unless (send self :get :footstep-parameter)
(send self :gen-footstep-parameter))
(send self :get :footstep-parameter)
)
;; simple footstep gen
(:go-pos-params->footstep-list
(xx yy th ;; [mm] [mm] [deg]
&key ((:footstep-parameter prm) (send self :footstep-parameter))
((:default-half-offset defp) (cadr (memq :default-half-offset prm)))
((:forward-offset-length xx-max) (cadr (memq :forward-offset-length prm)))
((:outside-offset-length yy-max) (cadr (memq :outside-offset-length prm)))
((:rotate-rad th-max) (abs (rad2deg (cadr (memq :rotate-rad prm)))))
(gen-go-pos-step-node-func
#'(lambda
(mc leg leg-translate-pos)
(let ((cc (send (send mc :copy-worldcoords) :translate
(cadr (assoc leg leg-translate-pos)))))
(send cc :name leg)
cc))))
"Calculate foot step list from goal x position [mm], goal y position [mm], and goal yaw orientation [deg]."
(let* ((dx xx) (dy yy) (dth th)
(leg (if (eps= (float yy) 0.0)
(if (> th 0.0) :lleg :rleg)
(if (> yy 0.0) :lleg :rleg)))
(mc (apply #'midcoords 0.5 (send self :legs :end-coords :copy-worldcoords)))
(gc (send (make-coords :pos (float-vector xx yy 0) :rpy (float-vector (deg2rad th) 0 0)) :transform mc :world))
(leg-translate-pos
(mapcar #'(lambda (l)
(list l (scale (case l (:rleg -1) (:lleg 1)) defp)))
'(:rleg :lleg)))
(ret (list (funcall gen-go-pos-step-node-func mc (case leg (:lleg :rleg) (:rleg :lleg)) leg-translate-pos))))
(labels ((do-push-steps
(finish-check func)
(until (funcall finish-check)
(funcall func)
(push (funcall gen-go-pos-step-node-func mc leg leg-translate-pos) ret)
(setq leg (case leg (:lleg :rleg) (:rleg :lleg)))
)))
(do-push-steps #'(lambda ()
(and (eps= (float dx) 0.0)
(eps= (float dy) 0.0)
(eps= (float dth) 0.0)))
#'(lambda ()
(let ((ddx (cond
((< xx-max dx) xx-max)
((> (- xx-max) dx) (- xx-max))
(t dx)))
(ddy (case leg
(:rleg
(cond
((< 0.0 dy) 0.0)
((> (- yy-max) dy) (- yy-max))
(t dy)))
(:lleg
(cond
((< yy-max dy) yy-max)
((> 0.0 dy) 0.0)
(t dy)))
))
(ddth (cond
((< th-max dth) th-max)
((> (- th-max) dth) (- th-max))
(t dth))))
(send mc :translate (float-vector ddx ddy 0.0))
(send mc :rotate (deg2rad ddth) :z)
(let ((diff (send mc :transformation gc :local)))
(setq dx (elt (send diff :pos) 0) dy (elt (send diff :pos) 1) dth (rad2deg (elt (car (rpy-angle (send diff :rot))) 0)))))))
(push (funcall gen-go-pos-step-node-func mc leg leg-translate-pos) ret)
(reverse ret))))
(:go-pos-quadruped-params->footstep-list
(xx yy th ;; [mm] [mm] [deg]
&key (type :crawl))
"Calculate foot step list for quadruped walking from goal x position [mm], goal y position [mm], and goal yaw orientation [deg]."
(let ((biped-fsl (send self :go-pos-params->footstep-list xx yy th :forward-offset-length 100 :rotate-rad 3))
quadruped-fsl)
;; calculate foot step list for quad walk
(dolist (fs biped-fsl)
(let* ((fs-leg-name (send fs :name))
(offset (send (send self fs-leg-name :end-coords :copy-worldcoords) :transformation fs :world))
(target-arm-name))
(case type
(:crawl
(dolist (l (list fs-leg-name (case fs-leg-name (:lleg :larm) (:rleg :rarm))))
(push (list (make-coords :coords (send (send self l :end-coords :copy-worldcoords) :transform offset :world) :name l))
quadruped-fsl)))
(:trot
(push (mapcar #'(lambda (l)
(make-coords :coords (send (send self l :end-coords :copy-worldcoords) :transform offset :world) :name l))
(list fs-leg-name (setq target-arm-name (case fs-leg-name (:lleg :rarm) (:rleg :larm)))))
quadruped-fsl))
(:pace
(push (mapcar #'(lambda (l)
(make-coords :coords (send (send self l :end-coords :copy-worldcoords) :transform offset :world) :name l))
(list fs-leg-name (case fs-leg-name (:lleg :larm) (:rleg :rarm))))
quadruped-fsl))
(:gallop
(push (mapcar #'(lambda (l)
(make-coords :coords (send (send self l :end-coords :copy-worldcoords) :transform offset :world) :name l))
(list (case fs-leg-name (:rleg :rleg) (:lleg :rarm))
(case fs-leg-name (:rleg :lleg) (:lleg :larm))))
quadruped-fsl))
)))
(reverse quadruped-fsl)))
;; Support polygon methods
(:support-polygons
()
"Return support polygons."
(send-all (send-all support-polygons :body) :worldcoords)
support-polygons)
(:support-polygon
(name)
"Return support polygon.
If name is list, return convex hull of all polygons.
Otherwise, return polygon with given name"
(if (consp name)
(instance polygon :init :vertices (quickhull
(apply
#'append
(mapcar #'(lambda (nm)
(send (send self :support-polygon nm) :vertices))
name))))
(find name (send self :support-polygons) :test #'equal :key #'(lambda (x) (send x :name)))))
(:make-support-polygons
()