Main Content

externalForce

base を基準とする外力行列を構成

説明

fext = externalForce(robot,bodyname,wrench) は、bodyname で指定されたボディに外力 wrench を加えるための外力行列を構成します。これを inverseDynamics および forwardDynamics への入力として使用できます。wrench の入力は base 座標系のものと仮定されます。

fext = externalForce(robot,bodyname,wrench,configuration) は、wrench を指定された configurationbodyname の座標系のものと仮定して外力行列を構成します。力の行列 fext は base 座標系で与えられます。

すべて折りたたむ

与えられたロボット コンフィギュレーションに外力と重力がかかった結果のジョイント加速度を計算します。ロボット全体に対して重力が指定されている状態で、レンチが特定のボディに適用されています。

Robotics System Toolbox™ loadrobotから KUKA iiwa 14 ロボット モデルを読み込みます。ロボットは、rigidBodyTree オブジェクトとして指定されています。

データ形式を "row" に設定します。すべてのダイナミクス計算について、データ形式は "row" または "column" でなければなりません。

重力を設定します。既定では、重力はゼロと仮定されます。

kukaIIWA14 = loadrobot("kukaIiwa14",DataFormat="row",Gravity=[0 0 -9.81]);

kukaIIWA14 ロボットのホーム コンフィギュレーションを取得します。

q = homeConfiguration(kukaIIWA14);

ロボットにかかる外力を表すレンチ ベクトルを指定します。関数 externalForce を使用して外力行列を生成します。ロボット モデル、レンチがかかるエンドエフェクタ、レンチ ベクトル、および現在のロボット コンフィギュレーションを指定します。wrench"iiwa_link_ee_kuka" ボディ座標系を基準に指定されるため、ロボット コンフィギュレーション q を指定する必要があります。

wrench = [0 0 0.5 0 0 0.3];
fext = externalForce(kukaIIWA14,"iiwa_link_ee_kuka",wrench,q);

kukaIIWA14 がホーム コンフィギュレーションにあるときにエンドエフェクタ "iiwa_link_ee_kuka" に外力を適用した状態で、重力による結果のジョイント加速度を計算します。ジョイント速度とジョイント トルクはゼロと仮定されます (空のベクトル [] として入力)。

qddot = forwardDynamics(kukaIIWA14,q,[],[],fext)
qddot = 1×7

   -0.0023   -0.0112    0.0036   -0.0212    0.0067   -0.0075  499.9920

関数 externalForce を使用して、剛体ツリー モデルに適用する力行列を生成します。力行列は、ロボットのジョイントごとに 6 要素のレンチを適用するための 1 つの行がある、m 行 6 列のベクトルです。関数 externalForce を使用し、エンドエフェクタを指定して、レンチを行列の正しい行に適切に割り当てます。複数の力行列を一緒に追加して、複数の力を 1 つのロボットに適用できます。

これらの外力に対抗するジョイント トルクを計算するには、関数 inverseDynamics を使用します。

Robotics System Toolbox™ loadrobotから Universal Robots UR5e を読み込みます。rigidBodyTree オブジェクトとして指定されます。重力を更新し、データ形式を "row" に設定します。すべてのダイナミクス計算について、データ形式は "row" または "column" でなければなりません。

manipulator = loadrobot("universalUR5e", DataFormat="row", Gravity=[0 0 -9.81]);
showdetails(manipulator)
--------------------
Robot: (10 bodies)

 Idx                Body Name                         Joint Name                         Joint Type                Parent Name(Idx)   Children Name(s)
 ---                ---------                         ----------                         ----------                ----------------   ----------------
   1                     base         base_link-base_fixed_joint                              fixed                    base_link(0)   
   2        base_link_inertia        base_link-base_link_inertia                              fixed                    base_link(0)   shoulder_link(3)  
   3            shoulder_link                 shoulder_pan_joint                           revolute            base_link_inertia(2)   upper_arm_link(4)  
   4           upper_arm_link                shoulder_lift_joint                           revolute                shoulder_link(3)   forearm_link(5)  
   5             forearm_link                        elbow_joint                           revolute               upper_arm_link(4)   wrist_1_link(6)  
   6             wrist_1_link                      wrist_1_joint                           revolute                 forearm_link(5)   wrist_2_link(7)  
   7             wrist_2_link                      wrist_2_joint                           revolute                 wrist_1_link(6)   wrist_3_link(8)  
   8             wrist_3_link                      wrist_3_joint                           revolute                 wrist_2_link(7)   flange(9)  
   9                   flange                     wrist_3-flange                              fixed                 wrist_3_link(8)   tool0(10)  
  10                    tool0                       flange-tool0                              fixed                       flange(9)   
--------------------

manipulator のホーム コンフィギュレーションを取得します。

q = homeConfiguration(manipulator);

shoulder_link に外力を設定します。入力レンチ ベクトルは、base 座標系で表現されます。

fext1 = externalForce(manipulator,"shoulder_link",[0 0 0.0 0.1 0 0]);

エンドエフェクタ tool0 に外力を設定します。入力レンチ ベクトルは、tool0 座標系で表現されます。

fext2 = externalForce(manipulator,"tool0",[0 0 0.0 0.1 0 0],q);

外力と釣り合うために必要なジョイント トルクを計算します。力を合わせるには、力行列を足し合わせます。ジョイント速度とジョイント加速度はゼロと仮定されます ([] として入力)。

tau = inverseDynamics(manipulator,q,[],[],fext1+fext2)
tau = 1×6

   -0.0233  -52.4189  -14.4896   -0.0100    0.0100   -0.0000

入力引数

すべて折りたたむ

ロボット モデル。rigidBodyTree オブジェクトとして指定します。関数 externalForce を使用するには、DataFormat プロパティを "row" または "column" に設定します。

外力が加えられるボディの名前。string スカラーまたは文字ベクトルとして指定します。このボディの名前は、robot オブジェクト上のボディと一致していなければなりません。

データ型: char | string

ボディに加えられるトルクと力。[Tx Ty Tz Fx Fy Fz] ベクトルとして指定します。レンチの最初の 3 要素は、xyz 軸の周りのモーメントに対応します。最後の 3 要素は、同じ軸に沿った線形力です。ロボットの configuration を指定しない限り、レンチは base 座標系を基準とするものと仮定されます。

ロボット コンフィギュレーション。ロボット モデル内の固定されていないすべてのジョイント位置を含むベクトルとして指定します。コンフィギュレーションは、homeConfiguration(robot)randomConfiguration(robot) を使用するか、独自のジョイント位置を指定することによって生成できます。configuration のベクトル形式を使用するには、robotDataFormat プロパティを 'row' または 'column' に設定します。

出力引数

すべて折りたたむ

外力行列。n 行 6 列または 6 行 n 列の行列として返されます。ここで、n はロボットの速度の数 (自由度) です。形状は robotDataFormat プロパティに依存します。"row" データ形式では n 行 6 列の行列を使用します。"column" データ形式では 6 行 n 列の行列を使用します。

構成される行列には、指定したボディに関連する位置のゼロ以外の値のみがリストされます。力の行列を一緒に追加することで、複数のボディに対する複数の力を指定できます。外力行列は、ダイナミクス関数 inverseDynamics および forwardDynamics に外力を指定するのに使用します。

詳細

すべて折りたたむ

ダイナミクス プロパティ

ロボット ダイナミクスを操作するときは、rigidBody オブジェクトの以下のプロパティを使用してマニピュレーター ロボットの個々のボディの情報を指定します。

  • Mass — キログラム単位の剛体の質量。

  • CenterOfMass — 剛体の重心位置。[x y z] の形式のベクトルとして指定します。このベクトルは、ボディ座標系を基準とした剛体の重心位置をメートル単位で記述します。オブジェクト関数 centerOfMass は、ロボットの重心を計算する際にこれらの剛体プロパティ値を使用します。

  • Inertia — 剛体の慣性。[Ixx Iyy Izz Iyz Ixz Ixy] の形式のベクトルとして指定します。ベクトルは、キログラム平方メートル単位でボディ座標系を基準としています。慣性テンソルは、次の形式の正定値行列です。

    A 3-by-3 matrix. The first row contains Ixx, Ixy, and Ixz. The second contains Ixy, Iyy, and Iyz. The third contains Ixz, Iyz, and Izz.

    Inertia ベクトルの最初の 3 要素は、慣性テンソルの対角要素である慣性モーメントです。最後の 3 要素は、慣性テンソルの非対角要素である慣性乗積です。

マニピュレーター ロボット モデル全体に関連する情報については、以下の rigidBodyTree オブジェクト プロパティを指定します。

  • Gravity — ロボットにかかる重力加速度。[x y z] ベクトルとして指定します (m/s2)。既定では重力加速度はありません。

  • DataFormat — 運動学およびダイナミクス関数の入出力データ形式。"struct""row"、または "column" として指定します。

ダイナミクス方程式

マニピュレーターの剛体ダイナミクスは次の方程式で制御されます。

ddt[qq˙]=[q˙M(q)1(C(q,q˙)q˙G(q)J(q)TFExt+τ)]

次のようにも記述されます。

M(q)q¨=C(q,q˙)q˙G(q)J(q)TFExt+τ

ここで、次のようになります。

  • M(q) — 現在のロボット コンフィギュレーションに基づくジョイント空間の質量行列。この行列はオブジェクト関数 massMatrix を使用して計算します。

  • C(q,q˙) — コリオリ項。q˙ で乗算され、速度積を計算します。オブジェクト関数 velocityProduct を使用して速度積を計算します。

  • G(q) — 指定した重力 Gravity の位置を維持するためにすべてのジョイントに必要な重力トルクおよび力。重力トルクはオブジェクト関数 gravityTorque を使用して計算します。

  • J(q) — 指定したジョイント コンフィギュレーションの幾何学的ヤコビアン。幾何学的ヤコビアンはオブジェクト関数 geometricJacobian を使用して計算します。

  • FExt — 剛体にかかる外力の行列。外力はオブジェクト関数 externalForce を使用して生成します。

  • τ — 各ジョイントにベクトルとして直接かかるジョイントのトルクと力。

  • q,q˙,q¨ — それぞれ個々のベクトルとしての、ジョイント コンフィギュレーション、ジョイント速度、ジョイント加速度。回転ジョイントの場合は、ラジアン単位 (rad/s と rad/s2) で値をそれぞれ指定します。直進ジョイントの場合は、メートル単位 (m/s と m/s2) で指定します。

ダイナミクスを直接計算するには、オブジェクト関数 forwardDynamics を使用します。この関数は、上記の入力の指定した組み合わせに対してジョイント加速度を計算します。

特定の動きの組み合わせを得るには、オブジェクト関数 inverseDynamics を使用します。この関数は、指定したコンフィギュレーション、速度、加速度、外力を得るために必要なジョイント トルクを計算します。

参照

[1] Featherstone, Roy. Rigid Body Dynamics Algorithms. Springer US, 2008. DOI.org (Crossref), doi:10.1007/978-1-4899-7560-7.

拡張機能

バージョン履歴

R2017a で導入

すべて展開する