![見出し画像](https://assets.st-note.com/production/uploads/images/75858944/rectangle_large_type_2_9d9b4bf6bf6ae2d4255ab75f37feca49.png?width=1200)
ROS入門 (62) - URDFに設定するinertiaの計算方法
URDFに設定するinertia(慣性モーメント)の計算方法をまとめました。
前回
1. 慣性モーメント
「慣性モーメント」は、物体の特定の軸を中心とした回転加速度に対する抵抗力です。物体の直線加速度に対する抵抗力が「質量」であるのに対し、回転加速度に対する抵抗力が「慣性モーメント」になります。記号では、I と表現し、単位は ML^2([mass]×[length]^2)になります。
物体全体の質量密度が一定で対称的な物体の場合、数式で慣性モーメントを求めることができます。
2. URDFでの慣性属性の設定
URDFでは、物理シミュレーションに対応するために慣性属性を追加する必要があります。
例えば、次のようなジオメトリ(geometry)を持つリンクの場合、
<geometry>
<box size="0.05 0.05 0.05" />
<geometry>
次のような慣性属性(inertial)を設定する必要があります。
<inertial>
<mass value="1.0">
<inertia ixx="0.00042" iyy="0.00042" izz="0.00042" ixy="0" ixz="0" iyz="0" />
</inertial>
・mass : 質量(kg)
・inertia : 慣性テンソル(ml^2)
intertiaが今回計算したい慣性モーメントのテンソル表現になります。対称行列なので、9要素のうち6要素のみを指定します。
![](https://assets.st-note.com/img/1649226725366-IXsTl9edW0.png?width=1200)
3. 慣性モーメントの計算
「慣性モーメント」の計算は、以下のサイトで紹介されている計算式が使えます。
・Box : 幅w、高さh、奥行きd、質量m の立方体
![](https://assets.st-note.com/img/1649225842166-MqcGjvrx9e.png?width=1200)
![](https://assets.st-note.com/img/1649225805300-fcXGJdnroH.png?width=1200)
・Sphere : 半径r、質量m の個体球体
![](https://assets.st-note.com/img/1649225897212-NNEveDCFLy.png?width=1200)
![](https://assets.st-note.com/img/1649225903921-w4leQmP4RJ.png?width=1200)
・Cylinder : 半径r、高さh、質量m の固体円柱
![](https://assets.st-note.com/img/1649225922488-MnfnAOnTQJ.png?width=1200)
![](https://assets.st-note.com/img/1649225974005-F1jWCs3LI8.png?width=1200)
4. 慣性モーメントの計算スクリプト
慣性モーメントを毎回手で計算するのはやりたくないので、計算用のスクリプトを作成します。すでに作ってくれてる人がいたので、これをベースにPython3対応などいろいろ調整した版を作りました。
・inertia_calc.py
# Boxの計算
def calculate_box_inertia(m, w, d, h):
Iw = (m / 12.0) * (pow(d, 2) + pow(h, 2))
Id = (m / 12.0) * (pow(w, 2) + pow(h, 2))
Ih = (m / 12.0) * (pow(w, 2) + pow(d, 2))
print('BOX ixx="' + '{:.5f}'.format(Iw) + '" iyy="' + '{:.5f}'.format(Id) +
'" izz="' + '{:.5f}'.format(Ih) + '" ixy="0.0" ixz="0.0" iyz="0.0"')
# Sphereの計算
def calculate_sphere_inertia(m, r):
I = (2 * m * pow(r, 2)) / 5.0
print('SPHERE ixx="' + '{:.5f}'.format(I) + '" iyy="' + '{:.5f}'.format(I) +
'" izz="' + '{:.5f}'.format(I) + '" ixy="0.0" ixz="0.0" iyz="0.0"')
# Cylinderの計算
def calculate_cylinder_inertia(m, r, h):
Ix = (m / 12.0) * (3 * pow(r, 2) + pow(h, 2))
Iy = Ix
Iz = (m * pow(r, 2)) / 2.0
print('Cylinder ixx="' + '{:.5f}'.format(Ix) + '" iyy="' + '{:.5f}'.format(Iy) +
'" izz="' + '{:.5f}'.format(Iz) + '" ixy="0.0" ixz="0.0" iyz="0.0"')
# Inertia計算機
selection = "START"
while selection.upper() != "Q":
# メニューの表示
print("====================")
print("Geometryを選択してください:")
print("[1] Box width(x-axis)*depth(y-axis)*height(z-axis)")
print("[2] Sphere radius(r)")
print("[3] Cylinder radius(r)*height(h)")
print("[Q] 終了")
# メニュー項目の入力
selection = input(">>")
# パラメータの入力と計算
if selection == "1":
mass = float(input("mass>>"))
width = float(input("x-axis length>>"))
depth = float(input("y-axis length>>"))
height = float(input("z-axis length>>"))
calculate_box_inertia(m=mass, w=width, d=depth, h=height)
elif selection == "2":
mass = float(input("mass>>"))
radius = float(input("radius>>"))
calculate_sphere_inertia(m=mass, r=radius)
elif selection == "3":
mass = float(input("mass>>"))
radius = float(input("radius>>"))
height = float(input("height>>"))
calculate_cylinder_inertia(m=mass, r=radius, h=height)
使用例は、次のとおりです。
$ python inertia_calc.py
====================
Geometryを選択してください:
[1] Box width(x-axis)*depth(y-axis)*height(z-axis)
[2] Sphere radius(r)
[3] Cylinder radius(r)*height(h)
[Q] 終了
>>1
mass>>1.0
x-axis length>>0.05
y-axis length>>0.05
z-axis length>>0.05
BOX ixx="0.00042" iyy="0.00042" izz="0.00042" ixy="0.0" ixz="0.0" iyz="0.0"