-
Notifications
You must be signed in to change notification settings - Fork 55
/
irtmodel.tex
2189 lines (1976 loc) · 84.2 KB
/
irtmodel.tex
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
\section{ロボットモデリング}
\subsection{ロボットのデータ構造とモデリング}
\subsubsection{ロボットのデータ構造と順運動学}
ロボットの構造はリンクと関節から構成されていると考えることが出来るが,
ロボットを関節とリンクに分割する方法として
\begin{itemize}
\item (a)切り離されるリンクの側に関節を含める
\item (b)胴体,あるいは胴体に近いほうに関節を含める
\end{itemize}
が考えられる.コンピュータのデータ構造を考慮し,
(a)が利用されている.その理由は胴体以外のすべてのリンクにおいて,
必ず関節を一つ含んだ構造となり,すべてのリンクを同一のアルゴリズムで扱う
ことが出きるためである.
この様に分割されたリンクを計算機上で表現するためにはツリー構造を利用する
ことが出来る.一般的にはツリー構造を作るときに二分木にすることでデータ構
造を簡略化することが多い.
ロボットのリンクにおける同次変換行列の求め方としては,関節回転座標系上に
原点をもつ$\Sigma_j$を設定し,親リンク座標系からみた回転軸ベクトルが
$a_j$, $\Sigma_j$の原点が$b_j$であり,回転の関節角度を$q_j$とする.
このとき$\Sigma_j$の親リンク相対の同次変換行列は
\[
{}^iT_j =
\left[
\begin{array}{cc}
e^{\hat{a}_jq_j} & b_j \\
0~0~0 & 1
\end{array}
\right]
\]
と書くことが出来る.
ここで,$e^{\hat{a}_jq_j}$は,一定速度の角速度ベクトルによって生ずる回
転行列を与える以下のRodriguesの式を用いている.これを回転軸$a$周りに
$wt[rad]$だけ回転する回転行列を与えるものとして利用している.
\[
e^{\hat{\omega}t} = E + \hat{a} sin (wt) + \hat{a}^2 (1 - cos(wt))
\]
親リンクの位置姿勢$p_i, R_i$が既知だとすると,$\Sigma_i$の同次変換行列を
\[
T_i =
\left[
\begin{array}{cc}
R_i & p_i \\
0~0~0 & 1
\end{array}
\right]
\]
と作ることができ,ここから
\[
T_j = T_i ~ {}^iT_j
\]
として計算できる.これをロボットのルートリンクから初めてすべてのリンクに
順次適用することでロボットの全身の関節角度情報から姿勢情報を算出すること
ができ,これを順運動学と呼ぶ.
\subsubsection{EusLispによる幾何情報のモデリング}
Euslispの幾何モデリングでは,基本モデル(body)の生成,bodyの合成関数,複
合モデル(bodyset)の生成と3つの段階がある.
これまでに以下のような基本モデルの生成,合成が可能な事を見てきている.
{\baselineskip=10pt
\begin{verbatim}
(setq c1 (make-cube 100 100 100))
(send c1 :locate #f(0 0 50))
(send c1 :rotate (deg2rad 30) :x)
(send c1 :set-color :yellow)
(objects (list c1))
(setq c2 (make-cylinder 50 100))
(send c2 :move-to
(make-coords
:pos #f(20 30 40)
:rpy (float-vector 0 0 (deg2rad 90)))
:world)
(send c2 :set-color :green)
(objects (list c1 c2))
(setq c3 (body+ c1 c2))
(setq c4 (body- c1 c2))
(setq c5 (body* c1 c2))
\end{verbatim}
}
bodysetはirteusで導入された複合モデルであり,bodyで扱えない複数の物体や
複数の色を扱うためのものである.
{\baselineskip=10pt
\begin{verbatim}
(setq c1 (make-cube 100 100 100))
(send c1 :set-color :red)
(setq c2 (make-cylinder 30 100))
(send c2 :set-color :green)
(send c1 :assoc c2) ;;; これを忘れいように
(setq b1 (instance bodyset :init
(make-cascoords)
:bodies (list c1 c2)))
(objects (list b1))
\end{verbatim}
}
\subsubsection{幾何情報の親子関係を利用したサンプルプログラム}
{\baselineskip=10pt
\begin{verbatim}
(setq c1 (make-cube 100 100 100))
(setq c2 (make-cube 50 50 50))
(send c1 :set-color :red)
(send c2 :set-color :blue)
(send c2 :locate #f(300 0 0))
(send c1 :assoc c2)
(objects (list c1 c2))
(do-until-key
(send c1 :rotate (deg2rad 5) :z)
(send *irtviewer* :draw-objects)
(x::window-main-one) ;; process window event
)
\end{verbatim}
}
\subsubsection{bodyset-linkとjointを用いたロボット(多リンク系)のモデリング}
irteusではロボットリンクを記述するクラスとしてbodyset-link(irtmodel.l)
というクラスが用意されている.これは機構情報と幾何情報をもち,一般的な木
構造でロボットの構造が表現されている.また,jointクラスを用いて関節情報
を扱っている.
{\baselineskip=10pt
\begin{verbatim}
(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))
\end{verbatim}
}
ジョイント(関節)のモデリングはjointクラス(irtmodel.l)を用いる.jointクラスは基底ク
ラスであり,実際にはrotational-joint, linear-joint等を利用する.
jointの子クラスで作られた関節は,:joint-angleメソッドで関節角度を指定す
ることが出来る.
{\baselineskip=10pt
\begin{verbatim}
(defclass joint
:super propertied-object
:slots (parent-link child-link joint-angle min-angle max-angle
default-coords))
(defmethod joint
(:init (&key name
((:child-link clink)) ((:parent-link plink))
(min -90) (max 90) &allow-other-keys)
(send self :name name)
(setq parent-link plink child-link clink
min-angle min max-angle max)
self))
(defclass rotational-joint
:super joint
:slots (axis))
(defmethod rotational-joint
(:init (&rest args &key ((:axis ax) :z) &allow-other-keys)
(setq axis ax joint-angle 0.0)
(send-super* :init args)
self)
(:joint-angle
(&optional v)
(when v
(setq relang (- v joint-angle) joint-angle v)
(send child-link :rotate (deg2rad relang) axis)))
joint-angle))
\end{verbatim}
}
ここでは,joint, parent-link, child-links, defualt-coordsを利用する.
簡単な1関節ロボットの例としてサーボモジュールを作ってみると
{\baselineskip=10pt
\begin{verbatim}
(defun make-servo nil
(let (b1 b2)
(setq b1 (make-cube 35 20 46))
(send b1 :locate #f(9.5 0 0))
(setq b2 (make-cylinder 3 60))
(send b2 :locate #f(0 0 -30))
(setq b1 (body+ b1 b2))
(send b1 :set-color :gray20)
b1))
(defun make-hinji nil
(let ((b2 (make-cube 22 16 58))
(b1 (make-cube 26 20 54)))
(send b2 :locate #f(-4 0 0))
(setq b2 (body- b2 b1))
(send b1 :set-color :gray80)
b2))
(setq h1 (instance bodyset-link :init (make-cascoords) :bodies (list (make-hinji))))
(setq s1 (instance bodyset-link :init (make-cascoords) :bodies (list (make-servo))))
(setq j1 (instance rotational-joint :init :parent-link h1 :child-link s1 :axis :z))
;; instance cascaded coords
(setq r (instance cascaded-link :init))
(send r :assoc h1)
(send h1 :assoc s1)
(setq (r . links) (list h1 s1))
(setq (r . joint-list) (list j1))
(send r :init-ending)
\end{verbatim}
}
となる.
ここでは,\verb|h1|,\verb|s1|という\verb|bodyset-link|と,
\verb|j1|という\verb|rotational-joint|を作成し,ここから
\verb|cascaded-link|という,連結リンクからなるモデルを生成している.
\verb|cascaded-link|は\verb|cascaded-coords|の子クラスであるため,
\verb|r (cascaded-link)|,\verb|h1|,\verb|s1|の座標系の親子関係を
\verb|:assoc|を利用して設定している.
\verb|(r . links)|という記法は\verb|r|というオブジェクトのスロット変数
(メンバ変数)である\verb|links|にアクセスしている.ここでは,
\verb|links|および\verb|joint-list|に適切な値をセットし,
\verb|(send r :init-ending)|として必要な初期設定を行っている.
これで\verb|r|という2つのリンクと1つの関節情報
を含んだ1つのオブジェクトを生成できる.これで例えば
\verb|(objects (list h1 s1))|ではなく,
\verb|(objects (list r))|としてロボットをビューワに表示できる.
また,\verb|(send r :locate #f(100 0 0))|などの利用も可能になっている.
\verb|cascaded-link|クラスのメソッドの利用例としては以下ある.
\verb|:joint-list|,\verb|:links|といった関節リストやリンクリストへの
アクセサに加え,関節角度ベクトルへのアクセスを提供する
\verb|:angle-vector|メソッドが重要である.これを引数なしで呼び出せば現
在の関節角度が得られ,これに関節角度ベクトルを引数に与えて呼び出せば,その引
数が示す関節角度ベクトルをロボットモデルに反映させることができる.
{\baselineskip=10pt
\begin{verbatim}
$ (objects (list r))
(#<servo-model #X628abb0 0.0 0.0 0.0 / 0.0 0.0 0.0>)
;; useful cascaded-link methods
$ (send r :joint-list)
(#<rotational-joint #X6062990 :joint101067152>)
$ (send r :links)
(#<bodyset-link #X62ccb10 :bodyset103598864 0.0 0.0 0.0 / 0.0 0.0 0.0>
#<bodyset-link #X6305830 :bodyset103831600 0.0 0.0 0.0 / 0.524 0.0 0.0>)
$ (send r :angle-vector)
#f(0.0)
$ (send r :angle-vector (float-vector 30))
#f(30.0)
\end{verbatim}
}
\subsubsection{cascaded-linkを用いたロボット(多リンク系)のモデリング}
一方で多リンク系のモデリング用のクラスとしてcascaded-linkというクラス
がある.
これには,links, joint-listというスロット変数があり,ここにbodyset-link,
ならびにjointのインスタンスのリストをバインドして利用する.
以下は,
\verb|cascaded-link|の子クラスを定義しここでロボットモデリングに
関する初期化処理を行うという書き方の例である.
{\baselineskip=10pt
\begin{verbatim}
(defclass cascaded-link
:super cascaded-coords
:slots (links joint-list bodies collision-avoidance-links))
(defmethod cascaded-link
(:init (&rest args &key name &allow-other-keys)
(send-super-lexpr :init args)
self)
(:init-ending
()
(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))
)
\end{verbatim}
}
{\baselineskip=10pt
\begin{verbatim}
(defclass servo-model
:super cascaded-link
:slots (h1 s1 j1))
(defmethod servo-model
(:init ()
(let ()
(send-super :init)
(setq h1 (instance bodyset-link :init (make-cascoords) :bodies (list (make-hinji))))
(setq s1 (instance bodyset-link :init (make-cascoords) :bodies (list (make-servo))))
(setq j1 (instance rotational-joint :init :parent-link h1 :child-link s1 :axis :z))
;; instance cascaded coords
(setq links (list h1 s1))
(setq joint-list (list j1))
;;
(send self :assoc h1)
(send h1 :assoc s1)
;;
(send self :init-ending)
self))
;;
;; (send r :j1 :joint-angle 30)
(:j1 (&rest args) (forward-message-to j1 args))
)
(setq r (instance servo-model :init))
\end{verbatim}
}
このようなクラスを定義して\verb|(setq r (instance servo-model :init))|
としても同じようにロボットモデルのインスタンスを作成することができ,先
ほどのメソッドを利用できる.クラス定義するメリットは
\verb|(:j1 (&rest args) (forward-message-to j1 args))|というメソッド定
義により,関節モデルのインスタンスへのアクセサを提供することができる.
これにより,特定の関節だけの値を知りたいとき,あるいは値をセットしたい
時には\verb|(send r :j1 :joint-angle)|や
\verb|(send r :j1 :joint-angle 30)|
という指示が可能になっている.
このロボットを動かす場合は前例と同じように
{\baselineskip=10pt
\begin{verbatim}
(objects (list r))
(dotimes (i 300)
(send r :angle-vector (float-vector (* 90 (sin (/ i 100.0)))))
(send *irtviewer* :draw-objects))
\end{verbatim}
}
などとするとよい.
{\baselineskip=10pt
\begin{verbatim}
(setq i 0)
(do-until-key
(send r :angle-vector (float-vector (* 90 (sin (/ i 100.0)))))
(send *irtviewer* :draw-objects)
(incf i))
\end{verbatim}
}
とすると,次にキーボードを押下するまでプログラムは動きつづける.
さらに,少し拡張して
これを用いて3リンク2ジョイントのロボットをモデリングした例が以下にな
る.:joint-angleというメソッドに\#f(0 0)というベクトルを引数に与えるこ
とで全ての関節角度列を指定することが出来る.
{\baselineskip=10pt
\begin{verbatim}
(defclass hinji-servo-robot
:super cascaded-link)
(defmethod hinji-servo-robot
(:init
()
(let (h1 s1 h2 s2 l1 l2 l3)
(send-super :init)
(setq h1 (make-hinji))
(setq s1 (make-servo))
(setq h2 (make-hinji))
(setq s2 (make-servo))
(send h2 :locate #f(42 0 0))
(send s1 :assoc h2)
(setq l1 (instance bodyset-link :init (make-cascoords) :bodies (list h1)))
(setq l2 (instance bodyset-link :init (make-cascoords) :bodies (list s1 h2)))
(setq l3 (instance bodyset-link :init (make-cascoords) :bodies (list s2)))
(send l3 :locate #f(42 0 0))
(send self :assoc l1)
(send l1 :assoc l2)
(send l2 :assoc l3)
(setq joint-list
(list
(instance rotational-joint
:init :parent-link l1 :child-link l2
:axis :z)
(instance rotational-joint
:init :parent-link l2 :child-link l3
:axis :z)))
(setq links (list l1 l2 l3))
(send self :init-ending)
)))
(setq r (instance hinji-servo-robot :init))
(objects (list r))
(dotimes (i 10000)
(send r :angle-vector (float-vector (* 90 (sin (/ i 500.0))) (* 90 (sin (/ i 1000.0)))))
(send *irtviewer* :draw-objects))
\end{verbatim}
}
\subsubsection{EusLispにおける順運動学計算}
順運動学計算を行うには,cascaded-corods, bodyset, bodyset-link 各クラ
スに定義された :worldcoords メソッドを用いる.
:worldcoords メソッドは,ルートリンクが見つかる(親リンクがなくなる)
か, スロット変数 changed が nil であるリンク
(一度順運動学計算を行ったことがある)が見つかるまで
さかのぼって親リンクの :worldcoords メソッドを呼び出すことで
順運動学計算を行う.
その際,スロット変数 changed を nil で上書く.
したがって,二度目の :worldcoords メソッドの呼び出しでは,一度計算され
たリンクの順運動学計算は行われず,即座にリンクの位置姿勢情報を取り出す
ことができる.
また,bodyset-link クラスの :worldcoords メソッドは, level 引数を取る
ことができ,それが :coords である場合には,リンクのもつ bodies スロット変数
の順運動学計算は行われない.
bodies にリンクの頂点を構成する faceset が含まれている場合には,これら
についての順運動学計算を省略することで大幅な高速化が期待できるだろう.
なお, level 引数の初期値には,リンクのもつ analysis-level スロット変数
が用いられるため,常に bodies の順運動学計算を行わない場合は,
リンクのインスタンス l について
\verb|(send l :analysis-level :coords)|
とすればよい.
{\baselineskip=10pt
\begin{verbatim}
(defmethod bodyset-link
(:worldcoords
(&optional (level analysis-level))
(case
level
(:coords (send-message self cascaded-coords :worldcoords))
(t (send-super :worldcoords)))
))
(defmethod bodyset
(:worldcoords
()
(when changed
(send-super :worldcoords)
(dolist (b bodies) (send b :worldcoords)))
worldcoords))
(defmethod cascaded-coords
(:worldcoords () ;calculate rot and pos in the world
(when changed
(if parent
(transform-coords (send parent :worldcoords) self
worldcoords)
(send worldcoords :replace-coords self))
(send self :update)
(setf changed nil))
worldcoords))
\end{verbatim}
}
\subsection{ロボットの動作生成}
%% \subsubsection{座標系の表現}
%% 特に断らない限り,添字のない物理量は絶対(世界)座標系で表したものとする.
%% 座標系$\Sigma_i$で表記した物理量は$^{i}p$のように左肩の添字で表現する.
%% 剛体の姿勢は直交行列で表し,座標系は右手系のみとする.
%% マ二ピュレータのエンドエフェクタの位置・姿勢は
%% 順運動学の式\eqref{forward-kinematics}によって与えられる.
%% \begin{eqnarray}
%% ^0_n\bm{H}(\bm{\theta}) = ^0_1\bm{H}(\theta_1)^1_2\bm{H}(\theta_2)
%% \dots ^{n-1}_n\bm{H}(\theta_n)
%% \eqlabel{forward-kinematics}
%% \end{eqnarray}
%% ここで, $^i_j\bm{H}$は座標系$\Sigma_i$から見た座標系$\Sigma_j$の
%% 相対位置・姿勢を表現する$4\times4$の同次変換行列である.
\subsubsection{逆運動学}
逆運動学においては, エンドエフェクタの位置・姿勢$^0_n\bm{H}$から
マニピュレータの関節角度ベクトル
$\bm{\theta}=(\theta_1, \theta_2, ..., \theta_n)^T$
を求める.
%% 同次変換行列$^0_n\bm{H}$は6自由度を有するので, $n \geq 6$であるマニピュレータに
%% 対しては解が複数存在, もしくは存在しない場合がある.
%% もちろんここでは, 逆運動学の目標が6自由度全てについて, 拘束するとは限ら
%% ないことに留意する必要がある.
%% ??
ここで, %%ルートリンクからの
エンドエフェクタの%%相対
位置・姿勢$\bm{r}$
は関節角度ベクトルを用いて
\begin{eqnarray}
\bm{r} = \bm{f}(\bm{\theta}) \eqlabel{forward-kinematics-functional}
\end{eqnarray}
とかける.
%%$\bm{r} = (x, y, z, \alpha, \beta, \gamma)^T$とすると
\eqref{forward-kinematics-functional}は\eqref{inverse-kinematics-func}
のように記述し,関節角度ベクトルを求める.
%%従って, 逆運動学を与える式は以下のように記述できる.
\begin{eqnarray}
\bm{\theta} = \bm{f}^{-1}(\bm{r}) \eqlabel{inverse-kinematics-func}
\end{eqnarray}
\eqlabel{inverse-kinematics-func}における$f^{-1}$は一般に非線形な関数となる.
そこで\eqlabel{forward-kinematics-functional}を時刻tに関して微分することで,
線形な式
\begin{eqnarray}
\dot{\bm{r}} &=& \frac{\partial \bm{f}}{\partial \bm{\theta}}
(\bm{\theta})\dot{\bm{\theta}} \\
&=& \bm{J}(\bm{\theta})\dot{\bm{\theta}}
\eqlabel{inverse-kinematics-base}
\end{eqnarray}
を得る.
ここで, $\bm{J}(\bm{\theta})$は$m \times n$のヤコビ行列である.
$m$はベクトル$\bm{r}$の次元, $n$はベクトル$\bm{\theta}$の次元である.
$\bm{\dot{r}}$は速度・角速度ベクトルである.
ヤコビ行列が正則であるとき逆行列$\bm{J}(\bm{\theta})^{-1}$を用いて
以下のようにしてこの線型方程式の解を得ることができる.
\begin{eqnarray}
\dot{\bm{\theta}} = \bm{J}(\bm{\theta})^{-1}\dot{\bm{r}}
\eqlabel{inverse-kinematics}
\end{eqnarray}
しかし, 一般にヤコビ行列は正則でないので,
ヤコビ行列の疑似逆行列$\bm{J}^{\#}(\bm{\theta})$
が用いられる(\eqref{psuedo-inverse-matrix}).
\begin{eqnarray}
\bm{A}^{\#} = \left\{
\begin{array}{l l}
& \bm{A}^{-1} \ ( m = n = rank \bm{A}) \\
& \bm{A}^T \ (\bm{A}\bm{A}^T)^{-1} ( n > m = rank \bm{A}) \\
& (\bm{A}^T\bm{A})^{-1}\bm{A}^T \ ( m > n = rank \bm{A})
\end{array}
\right.
\eqlabel{psuedo-inverse-matrix}
\end{eqnarray}
\eqref{inverse-kinematics-base}は,
$m>n$のときは\eqref{inverse-kinematics-error-func}を,
$n>=m$のときは\eqref{inverse-kinematics-min-func}を,
最小化する最小二乗解を求める問題と捉え,解を得る.
\begin{eqnarray}
\min_{\dot{\bm{\theta}}} \left(\dot{\bm{r}} - \bm{J}(\bm{\theta})\dot{\bm{\theta}}\right)^{T}
\left(\dot{\bm{r}} - \bm{J}(\bm{\theta})\dot{\bm{\theta}}\right)
\eqlabel{inverse-kinematics-error-func}
\end{eqnarray}
\begin{eqnarray}
\min_{\dot{\bm{\theta}}} & \dot{\bm{\theta}}^{T}\dot{\bm{\theta}}\\
\nonumber s.t. & \dot{\bm{r}} = \bm{J}(\bm{\theta})\dot{\bm{\theta}}
\eqlabel{inverse-kinematics-min-func}
\end{eqnarray}
関節角速度は次のように求まる.
\begin{eqnarray}
\dot{\bm{\theta}} = \bm{J}^{\#}(\bm{\theta})\dot{\bm{r}} +
\left(\bm{E}_n - \bm{J}^{\#}(\bm{\theta})\bm{J}(\bm{\theta})\right)\bm{z}
\eqlabel{inverse-kinematics-lagrangian-formula}
\end{eqnarray}
しかしながら, \eqref{inverse-kinematics-lagrangian-formula}に従って解を
求めると, ヤコビ行列$\bm{J}(\bm{\theta})$がフルランクでなくなる特異点に近づく
と, $\left|\dot{\bm{\theta}}\right|$が大きくなり不安定な振舞いが生じる.
そこで, Nakamura et al.のSR-Inverse\footnote{
Inverse kinematic solutions with singularity robustness for robot
manipulator control: Y.Nakamura and H. Hanafusa, Journal of Dynamic Systems, Measurement, and Control,
vol. 108, pp 163-171, 1986
}
を用いること
で, この特異点を回避する.
本研究では
ヤコビ行列の疑似逆行列$\bm{J}^{\#}(\bm{\theta})$の代わりに,
\eqref{SR-inverse-jacobian}に示す$\bm{J}^{*}(\bm{\theta})$
を用いる.
\begin{eqnarray}
\bm{J}^{*}(\bm{\theta})
= \bm{J}^T\left(\bm{J}\bm{J}^T + \epsilon \bm{E}_m\right)^{-1}
\eqlabel{SR-inverse-jacobian}
\end{eqnarray}
これは, \eqref{inverse-kinematics-error-func}の代わりに,
\eqref{SR-inverse-error-func}を最小化する最適化問題を
解くことにより得られたものである.
\begin{eqnarray}
\min_{\dot{\bm{\theta}}}
\{
\dot{\bm{\theta}}^T \dot{\bm{\theta}}
+
\epsilon
\left(\dot{\bm{r}} - \bm{J}(\bm{\theta})\dot{\bm{\theta}}\right)^T
\left(\dot{\bm{r}} - \bm{J}(\bm{\theta})\dot{\bm{\theta}}\right)
\}
\eqlabel{SR-inverse-error-func}
\end{eqnarray}
ヤコビ行列$\bm{J}(\bm{\theta})$が特異点に近づいているかの指標には
可操作度$\kappa(\bm{\theta})$\footnote{
ロボットアームの可操作度, 吉川恒夫, 日本ロボット学会誌, vol. 2, no. 1,
pp. 63-67, 1984.
}
が用いられる(\eqref{manipulability}).
\begin{eqnarray}
\kappa(\bm{\theta}) = \sqrt{\bm{J}(\bm{\theta}) \bm{J}^{T}(\bm{\theta})}
\eqlabel{manipulability}
\end{eqnarray}
%% 単腕マニピュレータのエンドエフェクタ位置姿勢$\bm{r}$と
%% 関節角度$\bm{\theta}$が以下のような関係にある場合,
%% \begin{equation}
%% \labeq{one-manipulator-pos-eq}
%% \bm{r} = f(\bm{\theta})
%% \end{equation}
%% エンドエフェクタ速度・角速度$\bm{\xi}$と
%% マニピュレータの関節角速度$\bm{\dot{\theta}}$の関係式は
%% 微分運動学に基づき以下のように求まる.
%% \begin{equation}
%% \labeq{one-manipulator-jacobi-eq}
%% \bm{\xi} = \bm{J} \bm{\dot{\theta}}
%% \end{equation}
%% ここで,$J$はマニピュレータのリンク系列におけるヤコビアン
%% $J=\frac{\partial \bm{f}}{\partial \bm{r}}$である.
微分運動学方程式における
タスク空間次元の選択行列\footnote{
Hybrid Position/Force Control: A Correct Formuration,
William D. Fisher, M. Shahid Mujtaba,
The Internationaltional Journal of Robotics Research,
vol. 11, no. 4, pp. 299-311, 1992.
}
は見通しの良い定式化のために省略するが,
以降で導出する全ての式において
適用可能であることをあらかじめことわっておく.
\subsubsection{基礎ヤコビ行列}
%%運動学拘束におけるのヤコビアン計算は
一次元対偶を関節に持つマニピュレータのヤコビアンは
基礎ヤコビ行列\footnote{
A unified approach for motion and force control of robot manipulators:
The operational space formulation,
O. Khatib, IEEE Journal of Robotics and Automation,
vol. 3, no. 1, pp. 43-53, 1987.
}
により
計算することが可能である.
基礎ヤコビ行列の第$j$関節に対応するヤコビアンの列ベクトル$\bm{J}_j$は
\begin{equation}
\label{eq:basic-jacobian-column-vector}
%%\begin{numcases}
\bm{J}_j=
\begin{cases}
\left[
\begin{array}{ccc}
\bm{a}_j\\
\bm{0}
\end{array}
\right]
& \text{if linear joint} \\
\left[
\begin{array}{ccc}
\bm{a}_j \times (\bm{p}_{end} - \bm{p}_j)\\
\bm{a}_j
\end{array}
\right]
& \text{if rotational joint}
%%\end{numcases}
\end{cases}
\end{equation}
と表される.
$\bm{a}_j$・$\bm{p}_j$はそれぞれ第$j$関節の関節軸単位ベクトル・位置ベクトルであり,
$\bm{p}_{end}$はヤコビアンで運動を制御するエンドエフェクタの位置ベクトルである.
上記では1自由度対偶の
回転関節・直動関節について導出したが,
その他の関節でもこれらの列ベクトルを
連結した行列としてヤコビアンを定義可能である.
非全方位台車の運動を表す2自由度関節は
前後退の直動関節と
旋回のための回転関節から構成できる.
全方位台車の運動を表す3自由度関節は
並進2自由度の直動関節と
旋回のための回転関節から構成できる.
球関節は姿勢を姿勢行列で,
姿勢変化を等価角軸変換によるものとすると,
3つの回転関節をつなぎ合わせたものとみなせる.
%% 単一マニピュレータにおける安定な逆運動学求解に関して
\subsubsection{関節角度限界回避を含む逆運動学}
ロボットマニピュレータの軌道生成において,
関節角度限界を考慮することはロボットによる実機実験の際に重要となる.
%%これは特に, ロボットの制御レベルにおいて,
%%インピーダンス制御を利用する際に重要となる.
本節では,文献\footnote{
Exploiting Task Intervals for Whole Body Robot Control,
Michael Gienger and Herbert Jansen and Christian Goeric
In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS'06), pp. 2484 - 2490, 2006}
\footnote{
\label{LimitAvoidance:Fung:RA95}
A weighted least-norm solution based scheme for avoiding jointlimits for redundant joint manipulators,
Tan Fung Chan and Dubey R.V.,
Robotics and Automation, IEEE Transactions on,
pp. 286-292,1995
}
%LimitAvoidanceHonda:Michael:IROS06, LimitAvoidance:Fung:RA95
の式および文章を引用しつつ, 関節角度限界の回避を
含む逆運動学について説明する.
重み付きノルムを以下のように定義する.
\begin{eqnarray}
\left|\bm{\dot{\theta}}\right|_{\bm{W}} =
\sqrt{\bm{\dot{\theta}}^T\bm{W}\bm{\dot{\theta}}}
\eqlabel{weighted-norm}
\end{eqnarray}
ここで, $\bm{W}$は$\bm{W} \in \bm{R}^{n \times n}$であり, 対象で全ての要
素が正である重み係数行列である.
この$\bm{W}$を用いて, $\bm{J}_{\bm{W}}, \bm{\dot{\theta}}_{\bm{W}}$を以下のよう
に定義する.
\begin{eqnarray}
\bm{J}_{\bm{W}} = \bm{J}\bm{W}^{-\frac{1}{2}},
\bm{\dot{\theta}}_{\bm{W}} = \bm{W}^{\frac{1}{2}}\bm{\dot{\theta}}
\end{eqnarray}
この$\bm{J}_{\bm{W}}, \bm{\dot{\theta}}_{\bm{W}}$を用いて, 以下の式を得
る.
\begin{eqnarray}
\dot{\bm{r}} & = & \bm{J}_{\bm{W}}\bm{\dot{\theta}}_{\bm{W}} \\
\left|\dot{\bm{\theta}}\right|_{\bm{W}} & = & \sqrt{\bm{\dot{\theta}}_{\bm{W}}^T\bm{\dot{\theta}}_{\bm{W}}}
\end{eqnarray}
これによって線型方程式の解は\footnoteref{LimitAvoidance:Fung:RA95}から
以下のように記述できる.
\begin{eqnarray}
\bm{\dot{\theta}}_{\bm{W}} = \bm{W}^{-1}\bm{J}^T
\left(\bm{J}\bm{W}^{-1}\bm{J}^T\right)^{-1}\dot{\bm{r}}
\end{eqnarray}
また、現在の関節角度$\theta$が関節角度限界$\theta_{i,\max},
\theta_{i, \min}$に対してどの程度余裕があるかを評価する
ための関数$H(\bm{\theta})$は以下のようになる\footnote{
%LimitPotential:Zghal:RA90
Efficient gradient projection optimization for manipulators
withmultiple degrees of redundancy,
Zghal H., Dubey R.V., Euler J.A.,
1990 IEEE International Conference on Robotics and Automation,
pp. 1006-1011, 1990.
}).
\begin{eqnarray}
H(\bm{\theta}) = \sum_{i = 1}^n\frac{1}{4}
\frac{(\theta_{i,\max} - \theta_{i,\min})^2}
{(\theta_{i,\max} - \theta_i)(\theta_i - \theta_{i,\min})}
\eqlabel{joint-performance-func}
\end{eqnarray}
次に\eqref{joint-weight-matrix}に示すような$n \times n$の重み係数行列
$\bm{W}$を考える.
\begin{eqnarray}
\bm{W} = \left[
\begin{array}{ccccc}
w_1 & 0 & 0 & \cdots & 0 \\
0 & w_2 & 0 & \cdots & 0 \\
\cdots & \cdots & \cdots & \ddots & \cdots \\
0 & 0 & 0 & \cdots & w_n \\
\end{array}
\right]
\eqlabel{joint-weight-matrix}
\end{eqnarray}
ここで$w_i$は
\begin{eqnarray}
w_i = 1 + \left|\frac{\partial \bm{H}(\bm{\theta})}{\partial \theta_i}\right|
\end{eqnarray}
である.
さらに\eqref{joint-performance-func}から次の式を得る.
\begin{eqnarray}
\frac{\partial H(\bm{\theta})}{\partial \theta_i}
= \frac{(\theta_{i,\max} - \theta_{i,\min})^2(2\theta_i -
\theta_{i,\max} - \theta_{i,\min})}
{4(\theta_{i,\max} - \theta_i)^2(\theta_i - \theta_{i,\min})^2}
\end{eqnarray}
関節角度限界から遠ざかる向きに関節角度が動いている場合には重み係数行列を
変化させる必要はないので,$w_i$を以下のように定義しなおす.
\begin{eqnarray}
w_i =
\left\{
\begin{array}{l l}
1 + \left|\frac{\partial \bm{H}(\bm{\theta})}{\partial \theta_i}\right|
& if \left|\frac{\partial \bm{H}(\bm{\theta})}{\partial
\theta_i}\right| \geq 0 \\
1 & if \left|\frac{\partial \bm{H}(\bm{\theta})}{\partial
\theta_i}\right| < 0
\end{array}
\right.
\end{eqnarray}
この$w_i$および$\bm{W}$を用いることで関節角度限界回避を含む逆運動学を解くこ
とができる.
%% 単一マニピュレータにおける安定な逆運動学求解に関して
\subsubsection{衝突回避を含む逆運動学}
ロボットの動作中での自己衝突や環境モデルとの衝突は
幾何形状モデルが存在すれば計算することが可能である.
ここではSugiura et al. により提案されている効率的な衝突回避計算
\footnote{
%NullspaceCollisionAvoidance:Sugiura:Humanoids06,
Real-Time Self Collision Avoidance for Humanoids by means of
Nullspace Criteria and Task Intervals,
H. Sugiura, M. Gienger, H. Janssen, C. Goerick,
Proceedings of the 2006 IEEE-RAS International Conference on Humanoid Robots,
pp. 575-580, 2006.
}
\footnote{
\label{WholebodyCollisionAvoidance:Sugiura:IROS07}
Real-time collision avoidance with whole body motion control for
humanoid robots,
Hisashi Sugiura, Michael Gienger, Herbert Janssen, Christian Goerick,
In Proceedings of the 2007 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS'07), pp. 2053 - 2068, 2007
}
を応用した動作生成法を示す.
実際の実装はSugiura et al. の手法に加え,
タスク作業空間のNullSpaceの利用を係数により制御できるようにした点や
擬似逆行列ではなくSR-Inverseを用いて特異点に
ロバストにしている点などが追加されている.
\subsubsection{衝突回避のための関節角速度計算法}
逆運動学計算における目標タスクと衝突回避の統合は
リンク間最短距離を用いたblending係数により行われる.
これにより,衝突回避の必要のないときは目標タスクを厳密に満し
衝突回避の必要性があらわれたときに目標タスクを
あきらめて衝突回避の行われる関節角速度計算を行うことが可能になる.
最終的な関節角速度の関係式は\refeq{collision-avoidance-all}で得られる.
以下では$ca$の添字は衝突回避計算のための成分を表し,
$task$の部分は衝突回避計算以外のタスク目標を表すことにする.
\begin{equation}
\labeq{collision-avoidance-all}
\bm{\dot{\theta}} = f(d)\bm{\dot{\theta}}_{ca}
+ \left(1-f(d)\right)\bm{\dot{\theta}}_{task}
\end{equation}
blending係数$f(d)$は,
リンク間距離$d$と閾値$d_a$・$d_b$の関数として計算される
(\refeq{collision-avoidance-blending-coefficient}).
\begin{eqnarray}
\labeq{collision-avoidance-blending-coefficient}
f(d) =
\left\{
\begin{array}{l l}
(d-d_a)/(d_b-d_a) & if d<d_a\\
0 & otherwise
\end{array}
\right.
\end{eqnarray}
$d_a$は衝突回避計算を行い始める値
(yellow zone\footnoteref{WholebodyCollisionAvoidance:Sugiura:IROS07})であり,
$d_b$は目標タスクを阻害しても衝突回避を行う閾値
(orange zone\footnoteref{WholebodyCollisionAvoidance:Sugiura:IROS07})である.
衝突計算をする2リンク間の最短距離・最近傍点が計算できた場合の
衝突を回避するための動作戦略は
2リンク間に作用する仮想的な反力ポテンシャルから導出される.
2リンク間の最近傍点同士をつなぐベクトル$\bm{p}$を用いた
2リンク間反力から導出される速度計算を
\refeq{collision-avoidance-distance-force}
に記す.
\begin{eqnarray}
\labeq{collision-avoidance-distance-force}
\bm{\delta x} =
\left\{
\begin{array}{l l}
0 & if \left|\bm{p}\right|>d_{a}\\
(d_{a}/\left|\bm{p}\right|-1)\bm{p} & else
\end{array}
\right.
\end{eqnarray}
これを用いた関節角速度計算は\refeq{collision-avoidance-joint-speed}
となる.
\begin{equation}
\labeq{collision-avoidance-joint-speed}
\dot{\bm{\theta}}_{ca} = \bm{J}_{ca}^{T} k_{joint} \bm{\delta x}
+ (\bm{E}_n - \bm{J}_{task}^{*}\bm{J}_{task}) \bm{J}_{ca}^{T} k_{null} \bm{\delta x}
\end{equation}
$k_{joint}$・$k_{null}$はそれぞれ反力ポテンシャルを
目標タスクのNullSpaceに分配するかそうでないかを制御する係数である.
\subsubsection{衝突回避計算例}
以下ではロボットモデル・環境モデルを用いた衝突回避例を示す.
本研究では,
ロボットのリンク同士,またはリンクと物体の衝突判定には,衝突判定ライブラリ
PQP(A Proximity Query Package)
\footnote{
Fast distance queries with rectangular swept sphere volumes,
Larsen E., Gottschalk S., Lin M.C., Manocha D,
Proceedings of The 2000 IEEE International Conference on Robotics and Automation, pp. 3719-3726, 2000.
% PQP:Larsen:ICRA00
}を用いた.
\reffig{collision-avoidance-example}では
$d_a = 200[mm]$,$d_b = 0.1 * d_a = 20[mm]$,
$k_{joint} = k_{null} = 1.0$と設定した.
この衝突判定計算では,衝突判定をリンクの設定を
\begin{enumerate}
\item リンクのリスト$n_{ca}$を登録
\item 登録されたリンクのリストから全リンクのペア$_{n_{ca}}C_2$を計算
\item 隣接するリンクのペア,常に交わりを持つリンクのペアなどを除外
\end{enumerate}
のように行うという工夫を行っている.
%%可能にする以下のような工夫を行っている。
%% $n_{ca}$個の登録されたリンクから
%% 衝突計算を行うリンクのペアの算定方法は、
%% 全てのリンク間の組み合わせ$_{n_{ca}}C_2$ではなく
%% 以下のように減らすことが妥当である。
%% なぜならほげほげ
%% \begin{enumerate}
%% \item \labitem{calc-link-pair0}
%% $task$用リンク系列よりリンク原点が同じものを除外。
%% これは、原点をリンク内にもち原点同士が交わるリンクの場合は
%% 原点が交わることが常に衝突していることとみなせるからである。
%% \item \labitem{calc-link-pair1}
%% \refitem{calc-link-pair1}から
%% \item \labitem{calc-link-pair2}
%% \refitem{calc-link-pair2}
%% \end{enumerate}
%% \begin{enumerate}
%% \item \labitem{calc-link-pair0}
%% $n_c$個のリンクが指定された場合,全てのリンク間
%% の組み合わせを算出(${n_c}_C_2$)
%% \item \labitem{calc-link-pair1}
%% 隣接するリンクのペアを除外
%% \item \labitem{calc-link-pair2}
%% 軸が交わるリンクのペアを除外
%% \end{enumerate}
\reffig{collision-avoidance-example}例では衝突判定をするリンクを
「前腕リンク」「上腕リンク」「体幹リンク」「ベースリンク」
の4つとして登録した.
この場合, $_4C_2$通りのリンクのペア数から
隣接するリンクが除外され,全リンクペアは
「前腕リンク-体幹リンク」
「前腕リンク-ベースリンク」
「上腕リンク-ベースリンク」
の3通りとなる.
\reffig{collision-avoidance-example}の3本の線(赤1本,緑2本)が
衝突形状モデル間での最近傍点同士をつないだ
最短距離ベクトルである.
全リンクペアのうち赤い線が最も距離が近いペアであり,
このリンクペアより衝突回避のための
逆運動学計算を行っている.
\begin{figure}[htb]
\begin{center}
\includegraphics[width=0.50\columnwidth]{fig/collision-avoidance-example.jpg}
\caption{Example of Collision Avoidance}
\labfig{collision-avoidance-example}
\end{center}
\end{figure}
%% PQP は SSV(Swept Sphere Volumes) を用い,三次元の物体同士の衝突判定,
%% 及び距離
%% 計算を高速に行う.ここで,SSV とは,点・線分・長方形の各形状プリミティ
%% ブを
%% 三次元的に膨張させて作成した BV(Bounding Volumes) セットであり,包含物
%% 体に
%% フィットした表現を可能とする特徴を持つ.
%% これら BV 要素同士の最短距離計算には,外部ボロノイ領域を考慮する,
%% Lin-Canny の
%% 最短距離計算アルゴリズム\cite{PQP:Lin91distance}を改良して用いる.
%% 二つの物体同士の距離計算は,各物体に対し,その物体の BV をノード
%% とするような探索木(BVH, Bounding Volume Hierarchies)を作成し,
%% 最短となる距離を再起的に計算していくことにより行う.
%% @INPROCEEDINGS{PQP:Lin91distance,