-
Notifications
You must be signed in to change notification settings - Fork 55
/
irtmodel.l
3675 lines (3598 loc) · 179 KB
/
irtmodel.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 :irtgeo)
(require :irtutil)
(require :pqp)
(defclass joint
:super propertied-object
:slots (parent-link child-link joint-angle min-angle max-angle default-coords
joint-velocity joint-acceleration joint-torque
max-joint-velocity max-joint-torque
joint-min-max-table joint-min-max-target))
(defmethod joint
(:init (&key (name (intern (format nil "joint~A" (sys::address self)) "KEYWORD"))
((:child-link clink)) ((:parent-link plink))
(min -90) (max 90) ;; use deg/mm unit
((:max-joint-velocity mjv)) ;; use SI(m/s,rad/s) unit
((:max-joint-torque mjt)) ;; use SI(N,Nm) unit
((:joint-min-max-table mm-table))
((:joint-min-max-target mm-target))
&allow-other-keys)
"abstract class of joint, users need to use rotational-joint, linear-joint, sphere-joint, 6dof-joint, wheel-joint or omniwheel-joint.
use :parent-link/:child-link for specifying links that this joint connect to and :min/:min for range of joint angle in degree."
(send self :name name)
(setq parent-link plink child-link clink
min-angle min max-angle max)
(if (or (and (float-vector-p mjv)
(not (v> mjv (instantiate float-vector (length mjv)))))
(and (not (float-vector-p mjv)) (< mjv 0.0)))
(error "[joint ~A] warning negative max-joint-velocity value ~A~%" name mjv))
(if (or (and (float-vector-p mjt)
(not (v> mjt (instantiate float-vector (length mjt)))))
(and (not (float-vector-p mjt)) (< mjt 0.0)))
(error "[joint ~A] warning negative max-joint-torque value ~A~%" name mjt))
(send self :max-joint-velocity mjv)
(send self :max-joint-torque mjt)
(send self :joint-min-max-table mm-table)
(send self :joint-min-max-target mm-target)
(setq default-coords (send child-link :copy-coords))
self)
(:min-angle (&optional v)
"If v is set, it updates min-angle of this instance. :min-angle returns minimal angle of this joint in degree."
(if v (setq min-angle v)) min-angle)
(:max-angle (&optional v)
"If v is set, it updates max-angle of this instance. :max-angle returns maximum angle of this joint in degree."
(if v (setq max-angle v)) max-angle)
(:parent-link (&rest args)
"Returns parent link of this joint. if any arguments is set, it is passed to the parent-link."
(user::forward-message-to parent-link args))
(:child-link (&rest args)
"Returns child link of this joint. if any arguments is set, it is passed to the child-link."
(user::forward-message-to child-link args))
(:calc-dav-gain (dav i periodic-time) (warn "subclass's respoinsibility (send ~s :calc-dav-gain)~%" self))
(:joint-dof ()
"Returns Degree of Freedom of this joint."
(warn "subclass's respoinsibility (send ~s :joint-dof)~%" self))
(:speed-to-angle (&rest args)
"Returns values in deg/mm unit of input value in SI(rad/m) unit."
(warn "subclass's respoinsibility (send ~s :speed-to-angle)~%" self))
(:angle-to-speed (&rest args)
"Returns values in SI(rad/m) unit of input value in deg/mm unit."
(warn "subclass's respoinsibility (send ~s :angle-to-speed)~%" self))
(:calc-jacobian (&rest args) (warn "subclass's respoinsibility (send ~s :calc-jacobian)~%" self))
(:joint-velocity (&optional jv)
"If jv is set, it updates joint-velocity of this instance. :joint-velocity returns velocity of this joint in SI(m/s, rad/s) unit."
(if jv (setq joint-velocity jv) joint-velocity))
(:joint-acceleration (&optional ja)
"If ja is set, it updates joint-acceleration of this instance. :joint-acceleration returns acceleration of this joint in SI(m/$s^2$, rad/$s^2$) unit."
(if ja (setq joint-acceleration ja) joint-acceleration))
(:joint-torque (&optional jt)
"If jt is set, it updates joint-torque of this instance. :joint-torque returns torque of this joint in SI(N, Nm) unit."
(if jt (setq joint-torque jt) joint-torque))
(:max-joint-velocity (&optional mjv)
"If mjv is set, it updates min-joint-velocity of this instance. :min-joint-velocity returns velocity of this joint in SI(m/s, rad/s) unit."
(if mjv (setq max-joint-velocity mjv) max-joint-velocity))
(:max-joint-torque (&optional mjt)
"If mjt is set, it updates min-joint-torque of this instance. :min-joint-torque returns velocity of this joint in SI(N, Nm) unit."
(if mjt (setq max-joint-torque mjt) max-joint-torque))
(:joint-min-max-table (&optional mm-table) (if mm-table (setq joint-min-max-table mm-table) joint-min-max-table))
(:joint-min-max-target (&optional mm-target) (if mm-target (setq joint-min-max-target mm-target) joint-min-max-target))
(:joint-min-max-table-angle-interpolate
(target-angle min-or-max)
(let* ((int-target-angle (floor target-angle)) ;; integer value convered as a matrix table key
(target-range (list int-target-angle (1+ int-target-angle))) ;; range of target-joint's angle, e.g., (car target-range) <= target-ang <= (cadr target-range)
(joint-range (mapcar #'(lambda (x)
(aref
joint-min-max-table
(case min-or-max
(:min-angle 1)
(:max-angle 2)
(t ))
(round
(-
(min (max (aref joint-min-max-table 0 0) x)
(aref joint-min-max-table 0 (- (array-dimension joint-min-max-table 1) 1)))
(aref joint-min-max-table 0 0)))
))
target-range)) ;; range of joint-angle based on target-range
(tmp-ratio (- target-angle (float int-target-angle))))
;; calc min max
;; interpolated joint-angle based on joint-range
;; e.g., (car joint-range) <= min[max]-angle <= (cadr joint-range) or (cadr joint-range) <= min[max]-angle <= (car joint-range)
(+ (* (car joint-range) (- 1 tmp-ratio)) (* (cadr joint-range) tmp-ratio))))
(:joint-min-max-table-min-angle
(&optional (target-angle (send joint-min-max-target :joint-angle)))
(send self :joint-min-max-table-angle-interpolate target-angle :min-angle))
(:joint-min-max-table-max-angle
(&optional (target-angle (send joint-min-max-target :joint-angle)))
(send self :joint-min-max-table-angle-interpolate target-angle :max-angle))
)
(defun calc-jacobian-default-rotate-vector
(paxis world-default-coords child-reverse transform-coords tmp-v3 tmp-m33)
(setq tmp-v3 (scale (if child-reverse -1.0 1.0)
(normalize-vector (send world-default-coords :rotate-vector paxis tmp-v3) tmp-v3) tmp-v3))
(transform (transpose (send transform-coords :worldrot) tmp-m33) tmp-v3 tmp-v3))
(defun calc-jacobian-rotational
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let* ((j-rot (calc-jacobian-default-rotate-vector ;; copied to tmp-v3
paxis world-default-coords child-reverse transform-coords tmp-v3 tmp-m33))
(p-diff (scale 1e-3 ;; scale [mm] -> [m], copied to tmp-v3a
(transform (transpose (send transform-coords :worldrot) tmp-m33)
(v- (send move-target :worldpos) (send child-link :worldpos) tmp-v3a)
tmp-v3a) tmp-v3a))
(j-trs (v* j-rot p-diff tmp-v3b))) ;; copied to tmp-v3b
(setq j-trs (calc-dif-with-axis j-trs translation-axis tmp-v0 tmp-v1 tmp-v2)) ;; copied to tmp-v3b, tmp-v0, tmp-v1 or tmp-v2
(dotimes (j (length j-trs)) (setf (aref fik (+ j row) column) (elt j-trs j)))
(setq j-rot (calc-dif-with-axis j-rot rotation-axis tmp-v0 tmp-v1 tmp-v2)) ;; copied to tmp-v3, tmp-v0, tmp-v1 or tmp-v2
(dotimes (j (length j-rot)) (setf (aref fik (+ j row (length j-trs)) column) (elt j-rot j)))
))
(defun calc-jacobian-linear
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let* ((j-trs (calc-jacobian-default-rotate-vector ;; copied to tmp-v3
paxis world-default-coords child-reverse transform-coords tmp-v3 tmp-m33))
(j-rot #f(0 0 0)))
(setq j-trs (calc-dif-with-axis j-trs translation-axis tmp-v0 tmp-v1 tmp-v2)) ;; copied to tmp-v3, tmp-v0, tmp-v1 or tmp-v2
(dotimes (j (length j-trs)) (setf (aref fik (+ j row) column) (elt j-trs j)))
(setq j-rot (calc-dif-with-axis j-rot rotation-axis tmp-v0 tmp-v1 tmp-v2)) ;; copied to j-rot, tmp-v0, tmp-v1 or tmp-v2
(dotimes (j (length j-rot)) (setf (aref fik (+ j row (length j-trs)) column) (elt j-rot j)))
))
;; calculate angle-speed gain used in :move-joints method
;; calc-angle-speed-gain-scalar -> for rotational-joint and linear-joint
(defun calc-angle-speed-gain-scalar
(j dav i periodic-time)
(let ((dav-gain
(abs (/ (send j :max-joint-velocity)
(/ (elt dav i) periodic-time)))))
(if (< dav-gain 1.0) dav-gain 1.0)))
;; calc-angle-speed-gain-vector -> for wheel-joint, omniwheel-joint, sphere-joint and 6dof-joint
(defun calc-angle-speed-gain-vector
(j dav i periodic-time)
(let ((dav-gain 1.0))
(dotimes (ii (send j :joint-dof))
(let ((tmp-gain
(abs (/ (elt (send j :max-joint-velocity) ii)
(/ (elt dav (+ ii i)) periodic-time)))))
(if (< tmp-gain dav-gain) (setq dav-gain tmp-gain))))
dav-gain))
(defclass rotational-joint
:super joint
:slots (axis))
(defmethod rotational-joint
(:init (&rest args
&key ((:axis ax) :z)
((:max-joint-velocity mjv) 5) ;; [rad/s]
((:max-joint-torque mjt) 100) ;; [Nm]
&allow-other-keys)
"create instance of rotational-joint. :axis is either (:x, :y, :z) or vector. :min-angle and :max-angle takes in radius, but velocity and torque are given in SI units."
(setq axis ax)
(setq joint-angle 0.0)
(send-super* :init
:max-joint-velocity mjv
:max-joint-torque mjt
args)
;; set default value
(if (null min-angle) (setq min-angle -90.0))
(if (null max-angle) (setq max-angle (+ 180.0 min-angle)))
(send self :joint-velocity 0.0) ;; [rad/s]
(send self :joint-acceleration 0.0) ;; [rad/s^2]
(send self :joint-torque 0.0) ;; [Nm]
self)
(:joint-angle
(&optional v &key relative &allow-other-keys)
"Return joint-angle if v is not set, if v is given, set joint angle. v is rotational value in degree."
(let ()
(when v
(when (and joint-min-max-table joint-min-max-target)
(setq min-angle (send self :joint-min-max-table-min-angle)
max-angle (send self :joint-min-max-table-max-angle)))
(if relative (setq v (+ v joint-angle)))
(cond ((> v max-angle)
(unless relative (warning-message 3 ";; ~A :joint-angle(~A) violate max-angle(~A)~%" self v max-angle))
(setq v max-angle)))
(cond ((< v min-angle)
(unless relative (warning-message 3 ";; ~A :joint-angle(~A) violate min-angle(~A)~%" self v min-angle))
(setq v min-angle)))
(setq joint-angle v)
(send child-link :replace-coords default-coords)
(send child-link :rotate (deg2rad joint-angle) axis))
joint-angle))
(:joint-dof () "Returns DOF of rotational joint, 1." 1)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-scalar self dav i periodic-time))
(:speed-to-angle (v) "Returns degree of given input in radian" (rad2deg v))
(:angle-to-speed (v) "Returns radian of given input in degree" (deg2rad v))
(:calc-jacobian (&rest args) (apply #'calc-jacobian-rotational args))
)
(defclass linear-joint
:super joint
:slots (axis))
(defmethod linear-joint
(:init (&rest args
&key ((:axis ax) :z)
((:max-joint-velocity mjv) (/ pi 4)) ;; [m/s]
((:max-joint-torque mjt) 100) ;; [N]
&allow-other-keys)
"Create instance of linear-joint. :axis is either (:x, :y, :z) or vector. :min-angle and :max-angle takes in [mm], but velocity and torque are given in SI units."
(setq axis
(if (float-vector-p ax)
ax
(case ax (:x (float-vector 1 0 0)) (:-x (float-vector -1 0 0))
(:y (float-vector 0 1 0)) (:-y (float-vector 0 -1 0))
(:z (float-vector 0 0 1)) (:-z (float-vector 0 0 -1)))))
(setq joint-angle 0.0)
(send-super* :init
:max-joint-velocity mjv
:max-joint-torque mjt
args)
;; set default value
(if (null min-angle) (setq min-angle -90.0))
(if (null max-angle) (setq max-angle 90.0))
(send self :joint-velocity 0.0) ;; [m/s]
(send self :joint-acceleration 0.0) ;; [m/s^2]
(send self :joint-torque 0.0) ;; [N]
self)
(:joint-angle
(&optional v &key relative &allow-other-keys)
"return joint-angle if v is not set, if v is given, set joint angle. v is linear value in [mm]."
(let ()
(when v
(if relative (setq v (+ v joint-angle)))
(when (> v max-angle)
(unless relative (warning-message 3 ";; ~A :joint-angle(~A) violate max-angle(~A)~%" self v max-angle))
(setq v max-angle))
(when (< v min-angle)
(unless relative (warning-message 3 ";; ~A :joint-angle(~A) violate min-angle(~A)~%" self v min-angle))
(setq v min-angle))
(setq joint-angle v)
(send child-link :replace-coords default-coords)
(send child-link :translate (scale joint-angle axis)))
joint-angle))
(:joint-dof () "Returns DOF of linear joint, 1." 1)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-scalar self dav i periodic-time))
(:speed-to-angle (v) "Returns [mm] of given input in [m]" (* 1000 v))
(:angle-to-speed (v) "Returns [m] of given input in [mm]" (* 0.001 v))
(:calc-jacobian (&rest args) (apply #'calc-jacobian-linear args))
)
(defclass wheel-joint
:super joint
:slots (axis))
(defmethod wheel-joint
(:init (&rest args
&key
(min (float-vector *-inf* *-inf*))
(max (float-vector *inf* *inf*))
((:max-joint-velocity mjv)
(float-vector (/ 0.08 0.05) ;; [m/s]
(/ pi 4))) ;; [rad/s]
((:max-joint-torque mjt)
(float-vector 100 100)) ;; [N] [Nm]
&allow-other-keys)
"Create instance of wheel-joint."
(setq joint-angle (float-vector 0 0))
(setq axis (list #f(1 0 0) :z))
(send-super* :init :min min :max max
:max-joint-velocity mjv
:max-joint-torque mjt
args)
;; set default value
self)
(:joint-angle
(&optional v &key relative &allow-other-keys)
"return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is (float-vector translation-x[mm] rotation-z[deg])"
(let (relvel relang)
(unless relative
(if v (warn "wheel-joint does not support non-relative mode??~%"))
(return-from :joint-angle joint-angle))
(when v
(setq relvel (elt v 0) relang (elt v 1))
(send child-link :translate (float-vector relvel 0 0))
(send child-link :rotate (deg2rad relang) :z)
)
joint-angle))
(:joint-dof () "Returns DOF of linear joint, 2." 2)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-vector self dav i periodic-time))
(:speed-to-angle (dv) "Returns [mm/deg] of given input in SI unit [m/rad]"
(float-vector (* 1000 (elt dv 0))
(rad2deg (elt dv 1))))
(:angle-to-speed (dv) "Returns SI unit [m/rad] of given input in [mm/deg]"
(float-vector (* 0.001 (elt dv 0))
(deg2rad (elt dv 1))))
(:calc-jacobian
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let ()
(calc-jacobian-linear
fik row column joint #f(1 0 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 1) joint #f(0 0 1) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
))
)
(defclass omniwheel-joint
:super joint
:slots (axis))
(defmethod omniwheel-joint
(:init (&rest args
&key
(min (float-vector *-inf* *-inf* *-inf*))
(max (float-vector *inf* *inf* *inf*))
((:max-joint-velocity mjv)
(float-vector (/ 0.08 0.05) (/ 0.08 0.05) ;; [m/s]
(/ pi 4))) ;; [rad/s]
((:max-joint-torque mjt)
(float-vector 100 100 100)) ;; [N] [N] [Nm]
&allow-other-keys)
"create instance of omniwheel-joint."
(setq joint-angle (float-vector 0 0 0))
(setq axis (list #f(1 0 0) #f(0 1 0) :z))
(send-super* :init :min min :max max
:max-joint-velocity mjv
:max-joint-torque mjt
args)
;; set default value
self)
(:joint-angle
(&optional v &key relative &allow-other-keys)
"return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is (float-vector translation-x[mm] translation-y[mm] rotation-z[deg])"
(when v
(if relative (setq v (v+ v joint-angle)))
(setq joint-angle (vmin (vmax v min-angle) max-angle))
(send child-link :replace-coords default-coords)
(send child-link :translate (float-vector (elt joint-angle 0) (elt joint-angle 1) 0))
(send child-link :rotate (deg2rad (elt joint-angle 2)) :z))
joint-angle)
(:joint-dof () "Returns DOF of linear joint, 3." 3)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-vector self dav i periodic-time))
(:speed-to-angle (dv) "Returns [mm/deg] of given input in SI unit [m/rad]"
(float-vector (* 1000 (elt dv 0))
(* 1000 (elt dv 1))
(rad2deg (elt dv 2))))
(:angle-to-speed (dv) "Returns SI unit [m/rad] of given input in [mm/deg]"
(float-vector (* 0.001 (elt dv 0))
(* 0.001 (elt dv 1))
(deg2rad (elt dv 2))))
(:calc-jacobian
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let ()
(calc-jacobian-linear
fik row column joint #f(1 0 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-linear
fik row (+ column 1) joint #f(0 1 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 2) joint #f(0 0 1) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
))
)
(defclass sphere-joint
:super joint
:slots (axis))
(defmethod sphere-joint
(:init (&rest args
&key
;; min/max are defined as a region of anguler velocity
(min (float-vector *-inf* *-inf* *-inf*))
(max (float-vector *inf* *inf* *inf*))
((:max-joint-velocity mjv)
(float-vector (/ pi 4) (/ pi 4) (/ pi 4))) ;; [rad/s]
((:max-joint-torque mjt)
(float-vector 100 100 100)) ;; [Nm] [Nm] [Nm]
&allow-other-keys)
"Create instance of sphere-joint. min/max are defind as a region of angular velocity in degree."
(setq axis (list :x :y :z))
(send-super* :init :min min :max max
:max-joint-velocity mjv
:max-joint-torque mjt
args)
;; joint-angle is defined as anguler velocity equivalent to orthogonal orientation matrix
(setq joint-angle (float-vector 0 0 0)) ;; [deg]
self)
(:joint-angle
(&optional v &key relative &allow-other-keys)
"return joint-angle if v is not set, if v is given, set joint angle.
v is joint-angle vector [deg] by axis-angle representation, i.e (scale rotation-angle-from-default-coords[deg] axis-unit-vector)"
(when v
;; Update joint-angle
(cond
(relative
;; if relative t
;; v is axis-angle difference vector calculated from difference-rotation or jacobian
(let ((vec (map float-vector #'deg2rad v)))
(unless (eps= (norm vec) 0.0 1e-20)
;; If vec is large, update joint-angle
(let ((drot (matrix-exponent (map float-vector #'deg2rad joint-angle))))
(m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)
(setq joint-angle (map float-vector #'rad2deg (matrix-log drot))))
)))
(t
;; if relative nil
;; v is axis-angle equivalent to orthogonal orientation matrix calculated from (send (send world-default-coords :transformation child-link) :worldrot)
(setq joint-angle v)))
;; min max check
(setq joint-angle (vmin (vmax joint-angle min-angle) max-angle))
;; update child-link
(send child-link :replace-coords default-coords)
(send child-link :transform
(make-coords :rot (matrix-exponent (map float-vector #'deg2rad joint-angle)))))
joint-angle)
(:joint-angle-rpy ;; v and return-value -> [deg] and (float-vector yaw roll pitch)
(&optional v &key relative)
"Return joint-angle if v is not set, if v is given, set joint-angle vector by RPY representation, i.e. (float-vector yaw[deg] roll[deg] pitch[deg])"
(when v
(let ((ja (if relative
(v+ (map float-vector #'deg2rad v)
(coerce (car (rpy-angle (matrix-exponent (map float-vector #'deg2rad joint-angle))))
float-vector))
(map float-vector #'deg2rad v))))
(send self :joint-angle (map cons #'rad2deg (matrix-log (rpy-matrix (elt ja 0) (elt ja 1) (elt ja 2)))))))
(map float-vector #'rad2deg (car (rpy-angle (matrix-exponent (map float-vector #'deg2rad joint-angle))))))
(:joint-dof () "Returns DOF of linear joint, 3." 3)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-vector self dav i periodic-time))
(:speed-to-angle (dv) "Returns degree of given input in radian"
(float-vector (rad2deg (elt dv 0))
(rad2deg (elt dv 1))
(rad2deg (elt dv 2))))
(:angle-to-speed (dv) "Returns radian of given input in degree"
(float-vector (deg2rad (elt dv 0))
(deg2rad (elt dv 1))
(deg2rad (elt dv 2))))
(:calc-jacobian
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let ()
(calc-jacobian-rotational
fik row column joint #f(1 0 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 1) joint #f(0 1 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 2) joint #f(0 0 1) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
))
;;
(:joint-euler-angle
(&key (axis-order '(:z :y :x)) ((:child-rot m) (send child-link :rot)))
"Return joint-angle if v is not set, if v is given, set joint-angle vector by euler representation."
(let ()
(map cons #'rad2deg
(case (length axis-order)
(1
(case (elt axis-order 0)
(:y
(list (atan2 (- (aref m 2 0)) (aref m 2 2))))
(:x
(list (atan2 (aref m 2 1) (aref m 2 2))))
(:z
(list (atan2 (aref m 1 0) (aref m 1 1))))))
(2
(case (elt axis-order 0)
(:y
(case (elt axis-order 1)
(:x (list (atan2 (- (aref m 2 0)) (aref m 0 0))
(atan2 (- (aref m 1 2)) (aref m 1 1))))
(:z (list (atan2 (aref m 0 2) (aref m 2 2))
(atan2 (aref m 1 0) (aref m 1 1))))
(:y (list 0 (atan2 (aref m 0 2) (aref m 0 0))))))
(:x
(case (elt axis-order 1)
(:y (list (atan2 (aref m 2 1) (aref m 1 1))
(atan2 (aref m 0 2) (aref m 0 0))))
(:z (list (atan2 (- (aref m 1 2)) (aref m 2 2))
(atan2 (- (aref m 0 1)) (aref m 0 0))))
(:x (list 0 (atan2 (aref m 2 1) (aref m 2 2))))))
(:z
(case (elt axis-order 1)
(:y (list (atan2 (- (aref m 0 1)) (aref m 1 1))
(atan2 (- (aref m 2 0)) (aref m 2 2))))
(:x (list (atan2 (aref m 1 0) (aref m 0 0))
(atan2 (aref m 2 1) (aref m 2 2))))
(:z (list 0 (atan2 (aref m 1 0) (aref m 1 1))))))))
(3
(matrix-to-euler-angle m axis-order)))
)))
)
(defclass 6dof-joint
:super joint
:slots (axis))
(defmethod 6dof-joint
;; translation (3dof) and rotation (3dof) -> 6dof
;; about rotation component -> please see sphere-joint declaration
(:init (&rest args
&key
(min (float-vector *-inf* *-inf* *-inf* *-inf* *-inf* *-inf*))
(max (float-vector *inf* *inf* *inf* *inf* *inf* *inf*))
((:max-joint-velocity mjv)
(float-vector (/ 0.08 0.05) (/ 0.08 0.05) (/ 0.08 0.05) ;; [m/s]
(/ pi 4) (/ pi 4) (/ pi 4))) ;; [rad/s]
((:max-joint-mjt mjt)
(float-vector 100 100 100 100 100 100)) ;; [N] [N] [N] [Nm] [Nm] [Nm]
(absolute-p nil)
&allow-other-keys)
"Create instance of 6dof-joint."
(setq axis (list #f(1 0 0) #f(0 1 0) #f(0 0 1) :x :y :z))
(send-super* :init :min min :max max
:max-joint-velocity mjv
:max-joint-torque mjt
args)
(if absolute-p
(let* ((c (send parent-link :transformation child-link))
(b (make-coords :pos (send default-coords :worldpos)))
(p (send b :inverse-transform-vector (send c :worldpos)))
(r (matrix-log (m* (transpose (send b :worldrot)) (send c :worldrot)))))
(setq joint-angle
(float-vector (elt p 0) (elt p 1) (elt p 2) ;; [mm]
(rad2deg (elt r 0)) (rad2deg (elt r 1)) (rad2deg (elt r 2)))) ;; [deg]
(setq default-coords b))
(setq joint-angle (float-vector 0 0 0 0 0 0))) ;; [mm] [deg]
self)
(:joint-angle
(&optional v &key relative &allow-other-keys) ;; v [mm] [deg]
"Return joint-angle if v is not set, if v is given, set joint angle vector, which is 6D vector of 3D translation[mm] and 3D rotation[deg], i.e. (find-if #'(lambda (x) (eq (send (car x) :name) 'sphere-joint)) (documentation :joint-angle))"
(when v
(let (joint-angle-pos joint-angle-rot)
;; Update joint-angle
;; translation
(setq joint-angle-pos (if relative
(v+ (subseq joint-angle 0 3) (subseq v 0 3))
(subseq v 0 3)))
;; rotation
(cond
(relative
;; if relative t
;; rotation part of v is axis-angle difference vector calculated from difference-rotation or jacobian
(let ((vec (map float-vector #'deg2rad (subseq v 3 6))))
(if (eps= (norm vec) 0.0 1e-20)
(setq joint-angle-rot (subseq joint-angle 3 6))
(let ((drot (matrix-exponent (map float-vector #'deg2rad (subseq joint-angle 3 6)))))
(m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)
(setq joint-angle-rot (map float-vector #'rad2deg (matrix-log drot))))
)))
(t
;; if relative nil
;; rotation part of v is axis-angle equivalent to orthogonal orientation matrix calculated from (send (send world-default-coords :transfor
(setq joint-angle-rot (subseq v 3 6))
))
(dotimes (i 3)
(setf (elt joint-angle i) (elt joint-angle-pos i))
(setf (elt joint-angle (+ i 3)) (elt joint-angle-rot i)))
;; min max check
(setq joint-angle (vmin (vmax joint-angle min-angle) max-angle))
;; update child-link
(send child-link :replace-coords default-coords)
(send child-link :transform
(make-coords :rot (matrix-exponent (map float-vector #'deg2rad joint-angle-rot)) :pos joint-angle-pos))))
joint-angle)
(:joint-angle-rpy ;; v and return-value -> [deg] and (float-vector yaw roll pitch)
(&optional v &key relative)
"Return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is 6D vector of 3D translation[mm] and 3D rotation[deg], for rotation, please see (find-if #'(lambda (x) (eq (send (car x) :name) 'sphere-joint)) (documentation :joint-angle-rpy))"
(when v
(let ((ja (if relative
(v+ (map float-vector #'deg2rad (subseq v 3 6))
(coerce (car (rpy-angle (matrix-exponent (map float-vector #'deg2rad (subseq joint-angle 3 6)))))
float-vector))
(map float-vector #'deg2rad (subseq v 3 6)))))
(send self :joint-angle (concatenate float-vector
(subseq v 0 3)
(map cons #'rad2deg (matrix-log (rpy-matrix (elt ja 0) (elt ja 1) (elt ja 2))))))))
(concatenate float-vector
(subseq joint-angle 0 3)
(map float-vector #'rad2deg (car (rpy-angle (matrix-exponent (map float-vector #'deg2rad (subseq joint-angle 3 6))))))))
(:joint-dof () "Returns DOF of linear joint, 6." 6)
(:calc-angle-speed-gain (dav i periodic-time) (calc-angle-speed-gain-vector self dav i periodic-time))
(:speed-to-angle (dv) "Returns [mm/deg] of given input in SI unit [m/rad]"
(float-vector (* 1000 (elt dv 0))
(* 1000 (elt dv 1))
(* 1000 (elt dv 2))
(rad2deg (elt dv 3))
(rad2deg (elt dv 4))
(rad2deg (elt dv 5))))
(:angle-to-speed (dv) "Returns SI unit [m/rad] of given input in [mm/deg]"
(float-vector (* 0.001 (elt dv 0))
(* 0.001 (elt dv 1))
(* 0.001 (elt dv 2))
(deg2rad (elt dv 3))
(deg2rad (elt dv 4))
(deg2rad (elt dv 5))))
(:calc-jacobian
(fik row column joint paxis child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(let ()
(calc-jacobian-linear
fik row column joint #f(1 0 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-linear
fik row (+ column 1) joint #f(0 1 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-linear
fik row (+ column 2) joint #f(0 0 1) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 3) joint #f(1 0 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 4) joint #f(0 1 0) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
(calc-jacobian-rotational
fik row (+ column 5) joint #f(0 0 1) child-link world-default-coords child-reverse
move-target transform-coords rotation-axis translation-axis
tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33)
))
)
;;;
;;;
(defclass bodyset-link
:super bodyset
:slots (joint parent-link child-links analysis-level default-coords
weight acentroid inertia-tensor
angular-velocity angular-acceleration
spacial-velocity spacial-acceleration
momentum-velocity angular-momentum-velocity
momentum angular-momentum
force moment ext-force ext-moment))
(defmethod bodyset-link
(:init
(coords
&rest args
&key
((:analysis-level level) :body)
((:weight w) 1)
((:centroid c) #f(0 0 0))
((:inertia-tensor i) (unit-matrix 3))
&allow-other-keys)
"Create instance of bodyset-link."
(setq analysis-level level)
(setq weight w inertia-tensor i acentroid c)
(send self :reset-dynamics)
(send-super* :init coords args))
(:worldcoords
(&optional (level analysis-level))
"Returns a coordinates object which represents this coord in the world by concatenating all the cascoords from the root to this coords."
(case
level
(:coords (send-message self cascaded-coords :worldcoords))
(t (send-super :worldcoords)))
)
(:analysis-level
(&optional v)
"Change analysis level :coords only changes kinematics level and :body changes geometry too."
(if v (setq analysis-level v)) analysis-level)
(:weight
(&optional w)
"Returns a weight of the link. If w is given, set weight."
(if w (setq weight w)) weight)
(:centroid
(&optional c)
"Returns a centroid of the link. If c is given, set new centroid."
(if c (setq acentroid c))
(send (send self :worldcoords) :transform-vector acentroid))
(:inertia-tensor
(&optional i)
"Returns a inertia tensor of the link. If c is given, set new intertia tensor."
(if i (setq inertia-tensor i)) inertia-tensor)
(:joint (&rest args) "Returns a joint associated with this link. If args is given, args are forward to the joint." (user::forward-message-to joint args))
(:add-joint (j) "Set j as joint of this link" (setq joint j))
(:del-joint () "Remove current joint of this link" (setq joint nil))
(:parent-link () "Returns parent link" parent-link)
(:child-links () "Returns child links" child-links)
(:add-child-links (l) "Add l to child links" (unless (or (member l child-links) (not l))(push l child-links)))
(:add-parent-link (l) "Set l as parent link" (setq parent-link l))
(:del-child-link (l) "Delete l from child links" (setq child-links (delete l child-links)))
(:del-parent-link () "Delete parent link" (setq parent-link nil))
(:default-coords (&optional c) (if c (setq default-coords c)) default-coords)
)
(defclass cascaded-link
:super cascaded-coords
:slots (links joint-list bodies
collision-avoidance-links
end-coords-list
))
(defmethod cascaded-link
(:init (&rest args
&key name
&allow-other-keys)
"Create cascaded-link."
(send-super-lexpr :init args)
self)
(:init-ending
()
"This method is to called finalize the instantiation of the cascaded-link. This update bodies and child-link and parent link from joint-list"
(setq bodies (flatten (send-all links :bodies)))
(dolist (j joint-list)
(send (send j :child-link) :add-joint j)
(send (send j :child-link) :add-parent-link (send j :parent-link))
(send (send j :parent-link) :add-child-links (send j :child-link))
)
(send self :update-descendants)
;; Make default collision shape
(dolist (l (send self :links)) (send l :make-collisionmodel))
)
(:links (&rest args) "Returns links, or args is passed to links" (user::forward-message-to-all links args))
(:joint-list (&rest args) "Returns joint list, or args is passed to joints" (user::forward-message-to-all joint-list args))
(:link (name) "Return a link with given name." (find name links :test #'equal :key #'(lambda (x) (send x :name))))
(:joint (name) "Return a joint with given name." (find name joint-list :test #'equal :key #'(lambda (x) (send x :name))))
(:end-coords
(name)
"Returns end-coords with given name"
(find name end-coords-list :test #'equal :key #'(lambda (x) (send x :name))))
(:bodies (&rest args) "Return bodies of this object. If args is given it passed to all bodies" (user::forward-message-to-all bodies args))
(:faces () "Return faces of this object." (flatten (send-all bodies :faces)))
(:update-descendants
(&rest args)
(send-all links :worldcoords))
(:angle-vector
(&optional vec
(angle-vector (instantiate float-vector (calc-target-joint-dimension joint-list))))
"Returns angle-vector of this object, if vec is given, it updates angles of all joint. If given angle-vector violate min/max range, the value is modified."
(let ((i 0))
(when vec
(when (> (length vec) (calc-target-joint-dimension joint-list))
(warn ";; WARNING : Dimension of input vector: ~A > Dimension of joint-list: ~A~%"
(length vec)
(calc-target-joint-dimension joint-list))))
(dolist (j joint-list)
(when vec
;; for joint w/ min-max-table, see http://sourceforge.net/p/jskeus/tickets/43/
(when (and (send j :joint-min-max-table) (send j :joint-min-max-target))
;; currently only 1dof joint is supported
(when (and (= (send j :joint-dof) 1) (= (send (send j :joint-min-max-target) :joint-dof) 1))
;; find index of joint-min-max-target
(let* ((ii 0) (jj (elt joint-list ii)) (ji 0)
tmp-joint-angle tmp-joint-min-angle tmp-joint-max-angle
tmp-target-joint-angle tmp-target-joint-min-angle tmp-target-joint-max-angle)
(while (not (eq jj (send j :joint-min-max-target)))
(incf ii) (incf ji (send jj :joint-dof)) (setq jj (elt joint-list ii)))
(setq tmp-joint-angle (elt vec i) tmp-target-joint-angle (elt vec ji))
(setq tmp-joint-min-angle (send j :joint-min-max-table-min-angle tmp-target-joint-angle)
tmp-joint-max-angle (send j :joint-min-max-table-max-angle tmp-target-joint-angle))
(setq tmp-target-joint-min-angle (send jj :joint-min-max-table-min-angle tmp-joint-angle)
tmp-target-joint-max-angle (send jj :joint-min-max-table-max-angle tmp-joint-angle))
(cond ((<= tmp-joint-min-angle tmp-joint-angle tmp-joint-max-angle) ;; ok
;; force change joint-angle to avoid problem
(setq (j . joint-angle) tmp-joint-angle
(jj . joint-angle) tmp-target-joint-angle))
(t
;;
(do ((i 0 (incf i 0.1)))
((> i 1))
(setq tmp-joint-min-angle (send j :joint-min-max-table-min-angle tmp-target-joint-angle)
tmp-joint-max-angle (send j :joint-min-max-table-max-angle tmp-target-joint-angle))
(setq tmp-target-joint-min-angle (send jj :joint-min-max-table-min-angle tmp-joint-angle)
tmp-target-joint-max-angle (send jj :joint-min-max-table-max-angle tmp-joint-angle))
(if (< tmp-joint-angle tmp-joint-min-angle)
(incf tmp-joint-angle (* (- tmp-joint-min-angle tmp-joint-angle) i)))
(if (> tmp-joint-angle tmp-joint-max-angle)
(incf tmp-joint-angle (* (- tmp-joint-max-angle tmp-joint-angle) i)))
(if (< tmp-target-joint-angle tmp-target-joint-min-angle)
(incf tmp-target-joint-angle (* (- tmp-target-joint-min-angle tmp-target-joint-angle) i)))
(if (> tmp-target-joint-angle tmp-target-joint-max-angle)
(incf tmp-target-joint-angle (* (- tmp-target-joint-max-angle tmp-target-joint-angle) i)))
)
(setq (j . joint-angle) tmp-joint-angle
(jj . joint-angle) tmp-target-joint-angle)
(setf (elt vec i) tmp-joint-angle)
(setf (elt vec ji) tmp-target-joint-angle)
)
);; cond
);; let*
)) ;; when
(case (send j :joint-dof)
(1 (send j :joint-angle (elt vec i)))
(t (send j :joint-angle (subseq vec i (+ i (send j :joint-dof)))))
))
(dotimes (k (send j :joint-dof))
(setf (elt angle-vector i)
(case (send j :joint-dof)
(1 (send j :joint-angle))
(t (elt (send j :joint-angle) k))))
(incf i)))
angle-vector))
;;
(:find-link-route
(to &optional from)
(let ((pl (send to :parent-link)))
(cond
;; if to is not included in (send self :links), just trace parent-link
((and pl (not (find to (send self :links))))
(send self :find-link-route pl from))
;; if (send self :links), append "to" link
((and pl (not (eq to from)))
(append (send self :find-link-route pl from) (list to)))
;; if link-route, just return "from" link
((and pl (eq to from))
(list from))
)))
(:link-list
(to &optional from)
"Find link list from to link to from link."
(let (ret1 ret2)
(setq ret1 (send self :find-link-route to from))
(when (and from (not (eq from (car ret1))))
(setq ret2 (send self :find-link-route from (car ret1)))
(setq ret1 (nconc (nreverse ret2) ret1))
)
ret1))
;; for min-max table
(:make-joint-min-max-table
(l0 l1 joint0 joint1
;; l0, l1 : link pair to be checked
;; joint0, joint1 : joint to be check min and max angle
&key (fat 0) (fat2 nil) (debug nil)
(margin 0.0) ;; margin [deg] is margin angle from collision-based min-angle and max-angle
(overwrite-collision-model nil))
;; initialize for :make-joint-min-max-table
(if (null debug) (send-all (send self :links) :analysis-level :coords))
;; for debug
(dolist (jj (list joint0 joint1))
(send jj :put :org-min-angle (send jj :min-angle))
(send jj :put :org-max-angle (send jj :max-angle)))
(let* ((pc (send self :copy-worldcoords))
(pav (send self :angle-vector))
(min-joint0 (truncate (- (send joint0 :min-angle) 1e-4)))
(max-joint0 (truncate (+ (send joint0 :max-angle) 1e-4)))
(min-joint1 (truncate (- (send joint1 :min-angle) 1e-4)))
(max-joint1 (truncate (+ (send joint1 :max-angle) 1e-4)))
(joint-range0 (1+ (round (- max-joint0 min-joint0))))
(joint-range1 (1+ (round (- max-joint1 min-joint1)))))
(when debug
(format t ";~10A ~20,10f ~20,10f~%" (send joint0 :name) (send joint0 :min-angle) (send joint0 :max-angle))
(format t ";~10A ~20,10f ~20,10f~%" (send joint1 :name) (send joint1 :min-angle) (send joint1 :max-angle))
(format t ";~10A ~20,10f ~20,10f~%" (send joint0 :name) min-joint0 max-joint0)
(format t ";~10A ~20,10f ~20,10f~%" (send joint1 :name) min-joint1 max-joint1))
(send self :newcoords (make-coords))
(send self :init-pose)
(when overwrite-collision-model
(setf (get l0 :pqpmodel) nil)
(setf (get l1 :pqpmodel) nil)
(collision-check l0 l1 geo::PQP_FIRST_CONTACT :fat fat :fat2 fat2))
(send self :make-min-max-table-using-collision-check
l0 l1 joint0 joint1 joint-range0 joint-range1 min-joint0 min-joint1 fat fat2 debug margin)
;; finalize for :make-joint-min-max-table
(send self :angle-vector pav)
(send self :newcoords pc)
(if (null debug) (send-all (send self :links) :analysis-level :body))
nil
))
(:make-min-max-table-using-collision-check
(l0 l1 joint0 joint1 joint-range0 joint-range1 min-joint0 min-joint1 fat fat2 debug margin)
;; put collision check results into collision matrix "col-mat".
(let ((col-mat (make-matrix joint-range1 joint-range0)))
;; col-mat : joint-range1 x joint-range0 matrix
;; collision-free region => 0
;; collision region => 1
(let (flag c (skip-count 10))
(do ((j 0 (+ j 1))) ((>= j joint-range1))
(send joint1 :joint-angle (round (+ j min-joint1)))
(setq flag :low-limit)
(when (= (mod j 10) 0)
(format t ";~c~7d/~7d" #x0d (* j joint-range0) (* joint-range0 joint-range1))
(finish-output))
(do ((i 0 (+ i 1))) ((>= i joint-range0))
(catch :min-max-collision-check
(send joint0 :joint-angle (round (+ i min-joint0)))
(cond
((and (eq flag :free) (/= (mod i skip-count) 0) (<= i (- joint-range0 skip-count)))
(setq c t))
(t
(setq c (= (collision-check l0 l1 geo::PQP_FIRST_CONTACT :fat fat :fat2 fat2) 0))
(cond
((and (eq flag :low-limit) c)
(setq flag :free))
((and (eq flag :free) (not c))
(setq flag :high-limit) (setq i (max (- i skip-count) 0))
(throw :min-max-collision-check nil))
)))
(setf (aref col-mat j i) (if c 1 0))
(if debug (format t ";~10A ~7,3f / ~10A ~7,3f / ~A ~A~%"
(send joint1 :name) (+ j min-joint1)
(send joint0 :name) (+ i min-joint0) c flag))
))))
(format t "~%")
;; generate min-max table from collision matrix
(labels
((gen-min-max-table-from-collision-matrix
(self-joint-range target-joint-range
self-min-joint target-min-joint
aref-func)
(let ((table (make-matrix 3 self-joint-range))) ;; row = self-joint-angle, target-min, target-max
(dotimes (i self-joint-range)
(let ((min-v (1+ self-joint-range)) (max-v 0) (flag nil))
(dotimes (j target-joint-range)
(when (= (funcall aref-func col-mat i j) 1)