Closed kochigami closed 8 years ago
https://github.com/euslisp/jskeus/blob/master/irteus/irtrobot.l#L166 ですね。
(send *pepper* :head :look-at (float-vector 900 50 900) :debug-view t)
するとheadのend-coordsがちゃんとついていないということで、peppereus/pepper.yamlを見ると
## TODO: end-coords tokuni base
となっていますね。例えば以下のようにしてpeppereusをコンパイルし直すとうまく行くと思います。 larm/rarm/lleg/rleg?のend-coordsもうまくつけてもらえると嬉しいです。
## end-coords
##
head-end-coords:
parent : CameraTop_frame
translate : [0, 0, 0]
rotate : [0, 1, 0, 90]
% end-coordsをちゃんと付けずにikをとくのは難しかったかも。。。
ご教示ありがとうございました。 元のend-coordsの定義はどこから来ているのかについても調べようと思います。
分かったこと:
:head :look-at
は顔のend-coordsに対して解くik
ikがうまく行かない時にend-coordsのことを気にする
pepper.yamlにend-coordsの記述はないが、
send *pepper* :head (:rarm, :larm, :rleg) :end-coords
をやってみると元々用意されている
しかしこの値がよくない
元々定義にあった send *pepper* :head :end-coords :draw-on :size 100 :flush t
などの結果
:debug-view t
のログの見方 (move-target: head-end-coordsの座標が悪いということで判断するらしい)
head-end-coords 変更前
send *pepper* :head :look-at (float-vector 900 50 900) :debug-view t
loop: 1
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X64683c0 :head-end-coords -38.0 0.0 169.9 / 0.053 0.637 0.0>)
targe-coordst: (#<coordinates #X6ad9948 900.0 50.0 900.0 / -0.033 0.908 -0.068>)
vel-pos :
vel-rot : 0.000 0.273
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.273/ 0.017
angle : 3.1 36.5
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.024 1102.752
cost : 0.025 1102.752
weight: 0.976 0.001
k : 0.000 (manipulability: 0.595, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 -0.001
J : -0.595 0.000
0.000 1.000
d(JJt): 0.354
J#t : -1.681 0.000
0.000 1.000
x : 0.000 0.273
J#x : -0.006 15.644
Ny : 0.000 0.000
dav : -0.006 15.644
dav^ : -0.006 15.644
loop: 2
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X64683c0 :head-end-coords -38.0 0.0 169.9 / 0.053 0.637 -6.939e-18>)
targe-coordst: (#<coordinates #X6b54af8 900.0 50.0 900.0 / -0.033 0.908 -0.068>)
vel-pos :
vel-rot : -0.000 0.273
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.273/ 0.017
angle : 3.0 36.5
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.025 1102.752
cost : 0.025 1102.752
weight: 1.000 0.001
k : 0.000 (manipulability: 0.595, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 -0.001
J : -0.595 0.000
-0.000 1.000
d(JJt): 0.354
J#t : -1.681 -0.000
-0.000 1.000
x : -0.000 0.273
J#x : 0.002 15.644
Ny : -0.000 -0.000
dav : 0.002 15.644
dav^ : 0.002 15.644
#f(3.16406 -1.9336 -4.39453 84.9902 10.0195 -70.0488 -19.9512 -39.1142 84.9902 -10.0195 70.0488 19.9512 39.1973 3.05176 36.5)
head-end-coords変更後
send *pepper* :head :look-at (float-vector 900 50 900) :debug-view t
loop: 1
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X6f5be00 :head-end-coords 48.01 0.0 332.74 / 0.0 1.571 0.0>)
targe-coordst: (#<coordinates #Xa268880 900.0 50.0 900.0 / -0.047 0.982 -0.088>)
vel-pos :
vel-rot : -0.044 -0.498
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.500/ 0.017
angle : 0.0 0.0
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost :100000000000000000000.000 100000000000000000000.000
cost : 0.000 0.155
weight: 1.000 1.000
k : 0.000 (manipulability: 1.000, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 -0.002
J : -1.000 0.000
0.000 1.000
d(JJt): 1.000
J#t : -1.000 0.000
0.000 1.000
x : -0.044 -0.498
J#x : 2.515 -28.537
Ny : 0.000 0.000
dav : 2.515 -28.537
dav^ : 2.330 -26.435
loop: 2
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -33.48 0.184 354.004 / 0.041 1.109 -1.388e-17>)
targe-coordst: (#<coordinates #X67f3180 900.0 50.0 900.0 / -0.052 1.04 -0.091>)
vel-pos :
vel-rot : -0.011 -0.067
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.068/ 0.017
angle : 2.3 -26.4
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.000 0.155
cost : 0.019 5.297
weight: 0.982 0.159
k : 0.000 (manipulability: 0.895, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 0.037
J : -0.895 -0.000
0.000 1.000
d(JJt): 0.802
J#t : -1.117 0.000
0.000 1.000
x : -0.011 -0.067
J#x : 0.699 -3.855
Ny : -0.000 0.000
dav : 0.699 -3.855
dav^ : 0.699 -3.855
loop: 3
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -45.853 -0.416 353.891 / 0.053 1.042 6.939e-18>)
targe-coordst: (#<coordinates #X6b8eb98 900.0 50.0 900.0 / -0.053 1.045 -0.092>)
vel-pos :
vel-rot : -0.000 0.006
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.006/ 0.017
angle : 3.0 -30.3
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.019 5.297
cost : 0.024 10.333
weight: 0.976 0.088
k : 0.000 (manipulability: 0.863, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 0.027
J : -0.863 0.000
-0.000 1.000
d(JJt): 0.746
J#t : -1.158 -0.000
-0.000 1.000
x : -0.000 0.006
J#x : 0.022 0.324
Ny : 0.000 0.000
dav : 0.022 0.324
dav^ : 0.022 0.324
loop: 4
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -44.813 -0.363 353.933 / 0.053 1.048 2.776e-17>)
targe-coordst: (#<coordinates #X6c97358 900.0 50.0 900.0 / -0.053 1.045 -0.092>)
vel-pos :
vel-rot : -0.000 -0.000
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.000/ 0.017
angle : 3.1 -30.0
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.024 10.333
cost : 0.025 9.689
weight: 0.976 1.000
k : 0.000 (manipulability: 0.866, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 0.302
J : -0.866 0.000
0.000 1.000
d(JJt): 0.751
J#t : -1.154 0.000
0.000 1.000
x : -0.000 -0.000
J#x : 0.000 -0.025
Ny : 0.000 0.000
dav : 0.000 -0.025
dav^ : 0.000 -0.025
loop: 5
union-link-list: (Neck Head)
move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -44.895 -0.368 353.93 / 0.053 1.047 0.0>)
targe-coordst: (#<coordinates #X6dcb630 900.0 50.0 900.0 / -0.053 1.045 -0.092>)
vel-pos :
vel-rot : -0.000 0.000
vel-pos-norm : 0.000/ 1.000
vel-rot-norm : 0.000/ 0.017
angle : 3.1 -30.0
min : -119.5 -40.5
max : 119.5 36.5
usrwei: 1.000 1.000
ocost : 0.025 9.689
cost : 0.025 9.738
weight: 0.976 0.093
k : 0.000 (manipulability: 0.866, gain: 0.001, limit: 0.100, len:2)
nspace: -0.000 0.028
J : -0.866 -0.000
0.000 1.000
d(JJt): 0.750
J#t : -1.155 0.000
0.000 1.000
x : -0.000 0.000
J#x : 0.000 0.002
Ny : -0.000 -0.000
dav : 0.000 0.002
dav^ : 0.000 0.002
#f(3.16406 -1.9336 -4.30664 84.9902 10.0195 -70.0488 -19.9512 -39.1142 84.9902 -10.0195 70.0488 19.9512 39.1973 3.05126 -29.9891)
end-coordsはJSK(jskeus)ローカルルールで headは目線の方向,前がz,xが下かな. 手はペットボトルを掴んだ時の手の中の(ロボットとてきには手を構成するポリゴンの外)の中心.zが上,xが前 で適当にエイヤと決めてください.
いまのPepperはpepper.yamlにend-coordsの指定が無いので,デフォルト値(リンクのルート)なので気にしなくていいです.
◉ Kei Okada
On Tue, Jul 19, 2016 at 8:25 PM, Kanae Kochigami notifications@github.com wrote:
ご教示ありがとうございました。 元のend-coordsの定義はどこから来ているのかについても調べようと思います。
[image: pepper-see-box-900-50-900] https://cloud.githubusercontent.com/assets/7259671/16948221/74ca7a72-4dee-11e6-812c-ba787193be4b.png
分かったこと: :head :look-at は顔のend-coordsに対して解くik ikがうまく行かない時にend-coordsのことを気にする
pepper.yamlにend-coordsの記述はないが、 send pepper :head (:rarm, :larm, :rleg) :end-coords をやってみると元々用意されている しかしこの値がよくない
元々定義にあった send pepper :head :end-coords :draw-on :size 100 :flush t などの結果 [image: end-coords] https://cloud.githubusercontent.com/assets/7259671/16947810/17ea08ce-4dec-11e6-9cd7-957fe0c38e72.png
:debug-view t のログの見方 (move-target: head-end-coordsの座標が悪いということで判断するらしい)
head-end-coords 変更前
send pepper :head :look-at (float-vector 900 50 900) :debug-view t loop: 1 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X64683c0 :head-end-coords -38.0 0.0 169.9 / 0.053 0.637 0.0>) targe-coordst: (#<coordinates #X6ad9948 900.0 50.0 900.0 / -0.033 0.908 -0.068>) vel-pos : vel-rot : 0.000 0.273 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.273/ 0.017 angle : 3.1 36.5 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.024 1102.752 cost : 0.025 1102.752 weight: 0.976 0.001 k : 0.000 (manipulability: 0.595, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 -0.001 J : -0.595 0.000 0.000 1.000 d(JJt): 0.354 J#t : -1.681 0.000 0.000 1.000 x : 0.000 0.273 J#x : -0.006 15.644 Ny : 0.000 0.000 dav : -0.006 15.644 dav^ : -0.006 15.644 loop: 2 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X64683c0 :head-end-coords -38.0 0.0 169.9 / 0.053 0.637 -6.939e-18>) targe-coordst: (#<coordinates #X6b54af8 900.0 50.0 900.0 / -0.033 0.908 -0.068>) vel-pos : vel-rot : -0.000 0.273 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.273/ 0.017 angle : 3.0 36.5 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.025 1102.752 cost : 0.025 1102.752 weight: 1.000 0.001 k : 0.000 (manipulability: 0.595, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 -0.001 J : -0.595 0.000 -0.000 1.000 d(JJt): 0.354 J#t : -1.681 -0.000 -0.000 1.000 x : -0.000 0.273 J#x : 0.002 15.644 Ny : -0.000 -0.000 dav : 0.002 15.644 dav^ : 0.002 15.644
f(3.16406 -1.9336 -4.39453 84.9902 10.0195 -70.0488 -19.9512 -39.1142 84.9902 -10.0195 70.0488 19.9512 39.1973 3.05176 36.5)
head-end-coords変更後
send pepper :head :look-at (float-vector 900 50 900) :debug-view t loop: 1 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X6f5be00 :head-end-coords 48.01 0.0 332.74 / 0.0 1.571 0.0>) targe-coordst: (#<coordinates #Xa268880 900.0 50.0 900.0 / -0.047 0.982 -0.088>) vel-pos : vel-rot : -0.044 -0.498 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.500/ 0.017 angle : 0.0 0.0 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost :100000000000000000000.000 100000000000000000000.000 cost : 0.000 0.155 weight: 1.000 1.000 k : 0.000 (manipulability: 1.000, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 -0.002 J : -1.000 0.000 0.000 1.000 d(JJt): 1.000 J#t : -1.000 0.000 0.000 1.000 x : -0.044 -0.498 J#x : 2.515 -28.537 Ny : 0.000 0.000 dav : 2.515 -28.537 dav^ : 2.330 -26.435 loop: 2 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -33.48 0.184 354.004 / 0.041 1.109 -1.388e-17>) targe-coordst: (#<coordinates #X67f3180 900.0 50.0 900.0 / -0.052 1.04 -0.091>) vel-pos : vel-rot : -0.011 -0.067 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.068/ 0.017 angle : 2.3 -26.4 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.000 0.155 cost : 0.019 5.297 weight: 0.982 0.159 k : 0.000 (manipulability: 0.895, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 0.037 J : -0.895 -0.000 0.000 1.000 d(JJt): 0.802 J#t : -1.117 0.000 0.000 1.000 x : -0.011 -0.067 J#x : 0.699 -3.855 Ny : -0.000 0.000 dav : 0.699 -3.855 dav^ : 0.699 -3.855 loop: 3 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -45.853 -0.416 353.891 / 0.053 1.042 6.939e-18>) targe-coordst: (#<coordinates #X6b8eb98 900.0 50.0 900.0 / -0.053 1.045 -0.092>) vel-pos : vel-rot : -0.000 0.006 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.006/ 0.017 angle : 3.0 -30.3 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.019 5.297 cost : 0.024 10.333 weight: 0.976 0.088 k : 0.000 (manipulability: 0.863, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 0.027 J : -0.863 0.000 -0.000 1.000 d(JJt): 0.746 J#t : -1.158 -0.000 -0.000 1.000 x : -0.000 0.006 J#x : 0.022 0.324 Ny : 0.000 0.000 dav : 0.022 0.324 dav^ : 0.022 0.324 loop: 4 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -44.813 -0.363 353.933 / 0.053 1.048 2.776e-17>) targe-coordst: (#<coordinates #X6c97358 900.0 50.0 900.0 / -0.053 1.045 -0.092>) vel-pos : vel-rot : -0.000 -0.000 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.000/ 0.017 angle : 3.1 -30.0 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.024 10.333 cost : 0.025 9.689 weight: 0.976 1.000 k : 0.000 (manipulability: 0.866, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 0.302 J : -0.866 0.000 0.000 1.000 d(JJt): 0.751 J#t : -1.154 0.000 0.000 1.000 x : -0.000 -0.000 J#x : 0.000 -0.025 Ny : 0.000 0.000 dav : 0.000 -0.025 dav^ : 0.000 -0.025 loop: 5 union-link-list: (Neck Head) move-target: (#<cascaded-coords #X6f5be00 :head-end-coords -44.895 -0.368 353.93 / 0.053 1.047 0.0>) targe-coordst: (#<coordinates #X6dcb630 900.0 50.0 900.0 / -0.053 1.045 -0.092>) vel-pos : vel-rot : -0.000 0.000 vel-pos-norm : 0.000/ 1.000 vel-rot-norm : 0.000/ 0.017 angle : 3.1 -30.0 min : -119.5 -40.5 max : 119.5 36.5 usrwei: 1.000 1.000 ocost : 0.025 9.689 cost : 0.025 9.738 weight: 0.976 0.093 k : 0.000 (manipulability: 0.866, gain: 0.001, limit: 0.100, len:2) nspace: -0.000 0.028 J : -0.866 -0.000 0.000 1.000 d(JJt): 0.750 J#t : -1.155 0.000 0.000 1.000 x : -0.000 0.000 J#x : 0.000 0.002 Ny : -0.000 -0.000 dav : 0.000 0.002 dav^ : 0.000 0.002
f(3.16406 -1.9336 -4.30664 84.9902 10.0195 -70.0488 -19.9512 -39.1142 84.9902 -10.0195 70.0488 19.9512 39.1973 3.05126 -29.9891)
— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/jsk-ros-pkg/jsk_roseus/issues/470#issuecomment-233604340, or mute the thread https://github.com/notifications/unsubscribe-auth/AAeG3Je6fBnWk2se2mGzDzFtekpjhkkzks5qXLRGgaJpZM4JPlam .
jskeusのマニュアルの中に
とあるのですが、このメソッドの使い方がよく分かりません。
:look-at
メソッドはどこに定義されているのでしょうか。 pepper-interface.l, naoqi-interface.l, robot-interface.lには見つかりませんでした。例えば、ペッパーで以下のように使ってみると、頭の上を物体に向けたような姿勢になってしまいます。