Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ImpedanceControllerのパラメータ設定について #1169

Open
hiroonda opened this issue Jun 24, 2017 · 7 comments
Open

ImpedanceControllerのパラメータ設定について #1169

hiroonda opened this issue Jun 24, 2017 · 7 comments

Comments

@hiroonda
Copy link

産総研の音田です。
ImpedanceControllerのパラメータ設定について質問があります。

インピーダンス制御のパラメータ、M, D, Kについて各軸異なる値を与えたいと考えた時に、
今の形ではM,D,K独立に値を与えられないように見えます。
(誤解しているかもしれませんが、下記のようになっているので、ある程度はできると言ってよいと思いますが、M, D, Kを行列で与えるようにはできないように見えます。)

http://wiki.ros.org/rtmros_nextage/Tutorials/Adding%20feedback%20control#Passing_Parameters_to_the_Impedance_Controller
を見ると、力のForce gain (x,y,z).に各軸異なる値を与えられるならば、
対角行列M, D, Kに対するパラメタをそれぞれm, d, kとして、(WikiではM_p, D_p, K_p等)
それぞれの軸の値を等価的には、
下記のように異なる値を設定したものと同じにできると言ってもよいと思います。
すなわち、
force gainをx, y, zで表さずに誤解のないようにwx, wy, wzと書きなおして、
ゲインを各軸異なる値に設定すれば、
M=[m/wx, m/wy, m/wz]
D=[d/wx , d/wy, d/wz]
K=[k/wx, k/wy, k/wz]
と設定するのと等価にはできるのかもしれません。
でも、これですとM, D, Kを独立には変えられないように見えます。

もし上記の認識が正しいとすると、

  1. 制御則の式を変更する
  2. M, D, Kについては、行列で与えられるようにインタフェースを変更する
    等の作業が必要となると思います。
    その際、hrpsys-base/rtc/ImpedanceController/ImpedanceController.cppの、
    // ref_force/ref_moment and force_gain/moment_gain are expressed in global coordinates.
    vel_p = ( param.force_gain * (abs_forces[it->first] - param.ref_force) * m_dt * m_dt
    + param.M_p * ( vel_pos1 - vel_pos0 )
    + param.D_p * ( dif_target_pos - vel_pos0 ) * m_dt
    + param.K_p * ( dif_pos * m_dt * m_dt ) ) /
    (param.M_p + (param.D_p * m_dt) + (param.K_p * m_dt * m_dt));
    vel_r = ( param.moment_gain * (abs_moments[it->first] - param.ref_moment) * m_dt * m_dt
    + param.M_r * ( vel_rot1 - vel_rot0 )
    + param.D_r * ( dif_target_rot - vel_rot0 ) * m_dt
    + param.K_r * ( dif_rot * m_dt * m_dt ) ) /
    (param.M_r + (param.D_r * m_dt) + (param.K_r * m_dt * m_dt));
    のあたりを変更することになるかと思いますが、正しいでしょうか。

もし誤解しておりましたらすみませんが、どのように考えればよいかも含めて、
ご教示いただけると助かります。よろしくお願いいたします。

@hiroonda
Copy link
Author

hiroonda commented Jul 2, 2017

I have a question about the ImpedanceController.
Would you give me some advice on how to set impedance parameters as follows?
M=diag(1, 2, 3)
D=diag(100, 220, 310)
K=diag(10.0, 20.5, 29.8).
(To simplify the explanation, the parameter values are changed to simple ones.)

PS.
Using force_gain, you may set approximately the following parameters.
M=diag(1, 2, 3),
D=diag(100, 200, 300),
K=diag(10, 20, 30),
where
force_gain = (1, 1/2, 1/3),
M_p=1,
D_p=100,
and K_p=10.

@7675t
Copy link

7675t commented Jul 2, 2017

こちらの件、正確な答えを持っているわけではないですが、おそらくコードを拡張して、少なくとも対角要素のパラメータを与えられるようにしなければ実現できないように思います。それができるようになったら嬉しいと思う1人です。

@snozawa
Copy link
Contributor

snozawa commented Jul 3, 2017

こちら遅くなりました。
おっしゃるとおり、現状は各軸独立に与えられないようになっております。

  1. M, D, Kについては、行列で与えられるようにインタフェースを変更する

こちらの変更が必要かと思います(中の計算もそれに合わせて若干変更がいるかもしれません)。
なお、研究室内部にこれの前身となるコードがあり、それではMDKが行列になっていましたが、
hrpsys-baseへ移植する際にスカラ値にかわっていたようです。
研究室の内部のコードではMDKが行列であったということもあり、
実はhrpsys-baseもそれに合わせて変更しようとしておりましたが、まだ手がつけられておりませんでした。

@hiroonda
Copy link
Author

hiroonda commented Jul 3, 2017

但馬さん、野沢さん、お忙しいところコメントと情報をありがとうございます。
各軸独立にパラメータ値を与えたいならば拡張が必要で、
M, D, Kについてインタフェースを変更する方向で進めるのがよいということですね。

#野沢先生、ご紹介していただいたような元になっているコードが既にあるならば、
#参考にしたほうがよいようにも思いますが、どうしたらよいでしょう。

@k-okada
Copy link
Contributor

k-okada commented Jul 3, 2017 via email

@hiroonda
Copy link
Author

hiroonda commented Jul 4, 2017

岡田先生、コメントをありがとうございます。
インピーダンスパラメタの選択に制限のかかった部分空間内からの選択でも今まで問題がなかったので、この拡張に優先度が低いのであれば、単純に今のImpedance Controllerを拡張することは控えた方がよいかもしれませんね。もし今まで皆さんが使用してきたプログラムの全てに該当箇所に関わる修正が必要になってしまうような副作用が起これば、良い選択ではないでしょうから。そんなことは望んでおりませんので、新たな命令として作成するなど他の選択肢をとるのがよいのかと思います。どちらにしてもまず動くようなものを作成し、シミュレーションなどでテストして、採用されるかどうかは皆さんにご判断をいただくのだと思います。ここで採用されるようなレベルのものに持っていくにあたり、どこをどう拡張すればよいか等について、今回はまずそのテストの際のご助言をいただければと思っています。
また、JSKの技術レベルの高さと幅広いご経験の中で、今までご使用になってきて問題がなかったということについては、よい使用法があるとか、Nextageなど(ハードウェア的にもしくは制御的に)あまりかたくないロボットではインピーダンスパラメタの調整がそこまで必要なかったとか、対象としてきた作業にそこまでの調整が必要がなかったとか、その理由についてもどうしてか知りたいところです。一般的に見える拡張を行ったように見えても、(どういう場合に)実質的に一緒だったり、あまり意味のないものになるのか、可能であればそれを共有させていただければと思います。

@k-okada
Copy link
Contributor

k-okada commented Feb 14, 2018

FYI @sshige

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants