Main Content

rigidBodyJoint

説明

rigidBodyJoint オブジェクトは、接続点を基準として剛体がどのように動くかを定義します。ツリー構造のロボットでは、ジョイントは常に特定の剛体に属し、各剛体に 1 つのジョイントがあります。

rigidBodyJoint オブジェクトでは、さまざまなタイプのジョイントを記述できます。rigidBodyTree で剛体ツリー構造を作成するときに、rigidBody クラスを使用して剛体に Joint オブジェクトを割り当てる必要があります。

サポートされているジョイント タイプの種類は次のとおりです。

  • fixed — 2 つのボディ間の相対運動を抑制する固定ジョイント。

  • revolute — 与えられた軸を中心に回転する単一自由度 (DOF) のジョイント。ピン ジョイントまたはヒンジ ジョイントとも呼ばれます。

  • prismatic — 与えられた軸に沿って並進する単一 DOF のジョイント。スライディング ジョイントとも呼ばれます。

  • floating — 任意の並進と回転を可能にする 6 DOF ジョイント。

定義される形状に応じて、ジョイント タイプごとに異なる次元のさまざまなプロパティがあります。

作成

説明

jointObj = rigidBodyJoint(jname) は、指定された名前をもつ固定ジョイントを作成します。

jointObj = rigidBodyJoint(jname,jtype) は、指定された名前をもつ指定されたタイプのジョイントを作成します。

入力引数

すべて展開する

ジョイント名。string スカラーまたは文字ベクトルとして指定します。剛体ツリーからアクセスできるように、ジョイント名は一意でなければなりません。

例: "elbow_right"

データ型: char | string

ジョイント タイプ。string スカラーまたは文字ベクトルとして指定します。ジョイントを作成する際、ジョイント タイプに応じて特定のプロパティが事前定義されます。

サポートされているジョイント タイプの種類は次のとおりです。

  • "fixed" — 2 つのボディ間の相対運動を抑制する固定ジョイント。

  • "revolute" — 与えられた軸を中心に回転する単一自由度 (DOF) のジョイント。ピン ジョイントまたはヒンジ ジョイントとも呼ばれます。

  • "prismatic" — 与えられた軸に沿って並進する単一 DOF のジョイント。スライディング ジョイントとも呼ばれます。

  • "floating" — 自由な並進と回転を可能にする 6 DOF ジョイント。

例: "prismatic"

データ型: char | string

プロパティ

すべて展開する

この プロパティ は読み取り専用です。

ジョイント タイプ。string スカラーまたは文字ベクトルとして返されます。ジョイントを作成する際、ジョイント タイプに応じて特定のプロパティが事前定義されます。

サポートされているジョイント タイプの種類は次のとおりです。

  • "fixed" — 2 つのボディ間の相対運動を抑制する固定ジョイント。

  • "revolute" — 与えられた軸を中心に回転する単一自由度 (DOF) のジョイント。ピン ジョイントまたはヒンジ ジョイントとも呼ばれます。

  • "prismatic" — 与えられた軸に沿って並進する単一 DOF のジョイント。スライディング ジョイントとも呼ばれます。

  • "floating" — 自由な並進と回転を可能にする 6 DOF ジョイント。

このジョイントを含む剛体をロボット モデルに追加する場合、replaceJoint を使用してジョイントを置き換えてジョイント タイプを変更する必要があります。

例: "prismatic"

データ型: char | string

ジョイント名。string スカラーまたは文字ベクトルとして返されます。剛体ツリーからアクセスできるように、ジョイント名は一意でなければなりません。このジョイントを含む剛体をロボット モデルに追加する場合、replaceJoint を使用してジョイントを置き換えてジョイント名を変更する必要があります。

例: "elbow_right"

データ型: char | string

ジョイントの位置範囲。ジョイントのタイプに応じて、[min max] 値の 2 要素の行ベクトルまたは [min max] 値の 7 行 2 列の行列として指定します。

  • fixed[NaN NaN] (既定)。固定ジョイントにはジョイントの範囲はありません。ボディは互いに固定されたままになります。

  • revolute[-pi pi] (既定)。軸を中心とする回転角度 (ラジアン単位) の範囲を定義します。

  • prismatic[-0.5 0.5] (既定)。軸に沿った線形運動 (メートル単位) の範囲を定義します。

  • "floating"[NaN(4,2); repmat([-5 5],3,1)] (既定)。四元数として表された回転には、ジョイントの範囲はありません。位置範囲の各行は、それぞれ x 軸、y 軸、および z 軸に沿った線形運動を定義します。

例: [-pi/2 pi/2]

ジョイントのホーム位置。ジョイント タイプに応じて、スカラーまたは 7 要素の行ベクトルとして指定します。ホーム位置は PositionLimits で設定された範囲内でなければなりません。このプロパティは、剛体ツリー全体の事前定義されたホーム コンフィギュレーションを生成するために homeConfiguration で使用されます。

ホーム位置の定義はジョイント タイプによって異なります。

  • fixed0 (既定)。固定ジョイントには関連するホーム位置はありません。

  • revolute0 (既定)。回転ジョイントのホーム位置は、ジョイント軸を中心とする回転角度 (ラジアン単位) で定義されます。

  • prismatic0 (既定)。直進ジョイントのホーム位置は、ジョイント軸に沿った線形運動 (メートル単位) で定義されます。

  • floating[1 0 0 0 0 0 0] (既定)。フローティング ジョイントには、恒等四元数と xyz 位置によって定義されるホーム位置があります。

例: revolute ジョイントについては pi/2 ラジアン

ジョイントの運動軸。3 要素の単位ベクトルとして指定します。このベクトルは、ローカル座標における 3 次元空間のいずれかの方向になります。

ジョイント軸の定義はジョイント タイプによって異なります。

  • fixed — 固定ジョイントには関連する運動軸はありません。

  • revolute — 回転ジョイントは、ジョイント軸に垂直な平面でボディを回転します。

  • prismatic — 直進ジョイントは、ジョイント軸の方向に沿った線形運動でボディを動かします。

  • floating — フローティング ジョイントでは、ボディは空間内で自由に回転します。フローティング ジョイントでは JointAxis プロパティを設定できません。

例: revolute ジョイントの x 軸を中心とする運動については [1 0 0]

この プロパティ は読み取り専用です。

ジョイントの座標系から親座標系への固定変換。4 行 4 列の同次変換行列として返されます。この変換により、ジョイントの先行座標系における点の座標が親ボディの座標系に変換されます。

例: eye(4)

この プロパティ は読み取り専用です。

子ボディの座標系からジョイントの座標系への固定変換。4 行 4 列の同次変換行列として返されます。この変換により、子ボディの座標系における点の座標がジョイントの後続座標系に変換されます。

例: eye(4)

オブジェクト関数

copyCreate copy of joint
setFixedTransformジョイントの固定変換プロパティを設定

すべて折りたたむ

剛体および対応するジョイントを剛体ツリーに追加します。それぞれの rigidBody オブジェクトは rigidBodyJoint オブジェクトを含み、addBody を使用して rigidBodyTree に追加しなければなりません。

剛体ツリーを作成します。

rbtree = rigidBodyTree;

固有の名前をもつ剛体を作成します。

body1 = rigidBody('b1');

回転ジョイントを作成します。既定で、rigidBody オブジェクトには固定ジョイントが付属します。body1.Joint プロパティに新しい rigidBodyJoint オブジェクトを割り当てることにより、ジョイントを置き換えます。

jnt1 = rigidBodyJoint('jnt1','revolute');
body1.Joint = jnt1;

剛体をツリーに追加します。剛体を接続するボディ名を指定します。最初のボディなので、ツリーのベース名を使用します。

basename = rbtree.BaseName;
addBody(rbtree,body1,basename)

ツリーに対して showdetails を使用して、剛体とジョイントが正しく追加されたことを確認します。

showdetails(rbtree)
--------------------
Robot: (1 bodies)

 Idx    Body Name   Joint Name   Joint Type    Parent Name(Idx)   Children Name(s)
 ---    ---------   ----------   ----------    ----------------   ----------------
   1           b1         jnt1     revolute             base(0)   
--------------------

Puma560® ロボットの Denavit-Hartenberg (DH) パラメーターを使用して、ロボットを構築します。各剛体は 1 つずつ追加され、子から親への変換がジョイント オブジェクトによって指定されます。

DH パラメーターは、各剛体がどのように親に接続されているかを基準として、ロボットのジオメトリを定義します。わかりやすくするために、Puma560 ロボットのパラメーターを行列で設定します [1]。Puma ロボットは連続チェーンのマニピュレーターです。DH パラメーターは、前のジョイント接続に対応する行列内の前の行との相対値です。

dhparams = [0   	pi/2	0   	0;
            0.4318	0       0       0
            0.0203	-pi/2	0.15005	0;
            0   	pi/2	0.4318	0;
            0       -pi/2	0   	0;
            0       0       0       0];

剛体ツリー オブジェクトを作成して、ロボットを構築します。

robot = rigidBodyTree;

最初の剛体を作成し、ロボットに追加します。剛体を追加するには次を行います。

  1. rigidBody オブジェクトを作成し、一意の名前を付けます。

  2. rigidBodyJoint オブジェクトを作成し、一意の名前を付けます。

  3. setFixedTransform を使用して、ボディからボディへの変換を DH パラメーターを使用して指定します。DH パラメーターの最後の要素である theta は無視されます。これは、角度がジョイント位置に依存するためです。

  4. addBody を呼び出して、最初のボディのジョイントをロボットの base 座標系に接続します。

body1 = rigidBody('body1');
jnt1 = rigidBodyJoint('jnt1','revolute');

setFixedTransform(jnt1,dhparams(1,:),'dh');
body1.Joint = jnt1;

addBody(robot,body1,'base')

その他の剛体を作成し、ロボットに追加します。addBody を呼び出して接続するときには、前述のボディ名を指定します。各固定変換は、前のジョイント座標系と相対的です。

body2 = rigidBody('body2');
jnt2 = rigidBodyJoint('jnt2','revolute');
body3 = rigidBody('body3');
jnt3 = rigidBodyJoint('jnt3','revolute');
body4 = rigidBody('body4');
jnt4 = rigidBodyJoint('jnt4','revolute');
body5 = rigidBody('body5');
jnt5 = rigidBodyJoint('jnt5','revolute');
body6 = rigidBody('body6');
jnt6 = rigidBodyJoint('jnt6','revolute');

setFixedTransform(jnt2,dhparams(2,:),'dh');
setFixedTransform(jnt3,dhparams(3,:),'dh');
setFixedTransform(jnt4,dhparams(4,:),'dh');
setFixedTransform(jnt5,dhparams(5,:),'dh');
setFixedTransform(jnt6,dhparams(6,:),'dh');

body2.Joint = jnt2;
body3.Joint = jnt3;
body4.Joint = jnt4;
body5.Joint = jnt5;
body6.Joint = jnt6;

addBody(robot,body2,'body1')
addBody(robot,body3,'body2')
addBody(robot,body4,'body3')
addBody(robot,body5,'body4')
addBody(robot,body6,'body5')

関数 showdetails または関数 show を使用して、ロボットが正しく構築されていることを確認します。showdetails は、すべてのボディを MATLAB® コマンド ウィンドウにリストします。show は、指定されたコンフィギュレーション (既定はホーム) でロボットを表示します。axis の呼び出しは、軸の範囲を変更し、軸ラベルを非表示にします。

showdetails(robot)
--------------------
Robot: (6 bodies)

 Idx    Body Name   Joint Name   Joint Type    Parent Name(Idx)   Children Name(s)
 ---    ---------   ----------   ----------    ----------------   ----------------
   1        body1         jnt1     revolute             base(0)   body2(2)  
   2        body2         jnt2     revolute            body1(1)   body3(3)  
   3        body3         jnt3     revolute            body2(2)   body4(4)  
   4        body4         jnt4     revolute            body3(3)   body5(5)  
   5        body5         jnt5     revolute            body4(4)   body6(6)  
   6        body6         jnt6     revolute            body5(5)   
--------------------
show(robot);
axis([-0.5,0.5,-0.5,0.5,-0.5,0.5])
axis off

参考文献

[1] Corke, P. I., and B. Armstrong-Helouvry. "A Search for Consensus among Model Parameters Reported for the PUMA 560 Robot." Proceedings of the 1994 IEEE International Conference on Robotics and Automation, IEEE Computer.Soc. Press, 1994, pp. 1608–13. DOI.org (Crossref), doi:10.1109/ROBOT.1994.351360.

既存の rigidBodyTree オブジェクトに変更を加えます。剛体ツリーのジョイント、ボディ、およびサブツリーを置換できます。

Robotics System Toolbox™ loadrobotから ABB IRB-120T マニピュレーターを読み込みます。rigidBodyTree オブジェクトとして指定します。

manipulator = loadrobot("abbIrb120T");

ロボットを with show で表示し、showdetails. を使用してロボットの詳細を読み取ります。

show(manipulator);

Figure contains an axes object. The axes object with xlabel X, ylabel Y contains 24 objects of type patch, line. These objects represent base_link, base, link_1, link_2, link_3, link_4, link_5, link_6, tool0, link_1_mesh, link_2_mesh, link_3_mesh, link_4_mesh, link_5_mesh, link_6_mesh, base_link_mesh.

showdetails(manipulator)
--------------------
Robot: (8 bodies)

 Idx     Body Name            Joint Name            Joint Type     Parent Name(Idx)   Children Name(s)
 ---     ---------            ----------            ----------     ----------------   ----------------
   1          base        base_link-base                 fixed         base_link(0)   
   2        link_1               joint_1              revolute         base_link(0)   link_2(3)  
   3        link_2               joint_2              revolute            link_1(2)   link_3(4)  
   4        link_3               joint_3              revolute            link_2(3)   link_4(5)  
   5        link_4               joint_4              revolute            link_3(4)   link_5(6)  
   6        link_5               joint_5              revolute            link_4(5)   link_6(7)  
   7        link_6               joint_6              revolute            link_5(6)   tool0(8)  
   8         tool0          joint6-tool0                 fixed            link_6(7)   
--------------------

プロパティを検査する特定のボディを取得します。link_3 ボディの唯一の子は link_4 ボディです。特定のボディをコピーすることもできます。

body3 = getBody(manipulator,"link_3");
childBody = body3.Children{1}
childBody = 
  rigidBody with properties:

            Name: 'link_4'
           Joint: [1x1 rigidBodyJoint]
            Mass: 1.3280
    CenterOfMass: [0.2247 1.5000e-04 4.1000e-04]
         Inertia: [0.0028 0.0711 0.0723 1.3052e-05 -1.3878e-04 -6.6037e-05]
          Parent: [1x1 rigidBody]
        Children: {[1x1 rigidBody]}
         Visuals: {'Mesh Filename link_4.stl'}
      Collisions: {'Mesh Filename link_4.stl'}

body3Copy = copy(body3);

link_3 ボディのジョイントを置き換えます。下流のボディ ジオメトリへの影響を確実に防ぐために、新しい Joint オブジェクトを作成し、replaceJoint を使用しなければなりません。必要に応じて、既定の単位行列を使用する代わりに、setFixedTransform を呼び出してボディ間の変換を定義します。

newJoint = rigidBodyJoint("prismatic");
replaceJoint(manipulator,"link_3",newJoint);

showdetails(manipulator)
--------------------
Robot: (8 bodies)

 Idx     Body Name            Joint Name            Joint Type     Parent Name(Idx)   Children Name(s)
 ---     ---------            ----------            ----------     ----------------   ----------------
   1          base        base_link-base                 fixed         base_link(0)   
   2        link_1               joint_1              revolute         base_link(0)   link_2(3)  
   3        link_2               joint_2              revolute            link_1(2)   link_3(4)  
   4        link_3             prismatic                 fixed            link_2(3)   link_4(5)  
   5        link_4               joint_4              revolute            link_3(4)   link_5(6)  
   6        link_5               joint_5              revolute            link_4(5)   link_6(7)  
   7        link_6               joint_6              revolute            link_5(6)   tool0(8)  
   8         tool0          joint6-tool0                 fixed            link_6(7)   
--------------------

removeBody を使用してボディ全体を削除し、結果のサブツリーを取得します。削除されたボディはサブツリーに含まれます。

subtree = removeBody(manipulator,"link_4")
subtree = 
  rigidBodyTree with properties:

     NumBodies: 4
        Bodies: {[1x1 rigidBody]  [1x1 rigidBody]  [1x1 rigidBody]  [1x1 rigidBody]}
          Base: [1x1 rigidBody]
     BodyNames: {'link_4'  'link_5'  'link_6'  'tool0'}
      BaseName: 'link_3'
       Gravity: [0 0 0]
    DataFormat: 'struct'

show(subtree);

Figure contains an axes object. The axes object with xlabel X, ylabel Y contains 12 objects of type patch, line. These objects represent link_3, link_4, link_5, link_6, tool0, link_4_mesh, link_5_mesh, link_6_mesh.

変更した link_3 ボディを削除します。コピーされた元の link_3 ボディを link_2 ボディに追加し、次に返されたサブツリーも追加します。ロボット モデルはそのままにします。showdetails で詳細な比較を確認します。

removeBody(manipulator,"link_3");
addBody(manipulator,body3Copy,"link_2")
addSubtree(manipulator,"link_3",subtree)

showdetails(manipulator)
--------------------
Robot: (8 bodies)

 Idx     Body Name            Joint Name            Joint Type     Parent Name(Idx)   Children Name(s)
 ---     ---------            ----------            ----------     ----------------   ----------------
   1          base        base_link-base                 fixed         base_link(0)   
   2        link_1               joint_1              revolute         base_link(0)   link_2(3)  
   3        link_2               joint_2              revolute            link_1(2)   link_3(4)  
   4        link_3               joint_3              revolute            link_2(3)   link_4(5)  
   5        link_4               joint_4              revolute            link_3(4)   link_5(6)  
   6        link_5               joint_5              revolute            link_4(5)   link_6(7)  
   7        link_6               joint_6              revolute            link_5(6)   tool0(8)  
   8         tool0          joint6-tool0                 fixed            link_6(7)   
--------------------

この例では、固定ベースで "floating" タイプの rigidBodyJoint で表されたフローティング ジョイントを使用して、剛体ツリーとしてフローティング ロボットをモデル化する方法を示します。この手法は、順運動学やダイナミクスなどのほとんどの用途で使用できます。ただし、フローティング ベースをもつロボットの逆運動学ソルバーまたは運動モデルを使用する必要がある場合、"floating" ジョイントは使用できません。逆運動学または運動モデル用にフローティングベースのロボットをモデル化するには、Inverse Kinematics for Robots with Floating Baseを参照してください。

まず、空の剛体ツリーとして固定ベースを作成します。次に、剛体を作成し、その剛体に "floating" タイプの剛体ジョイントを追加します。

rbt = rigidBodyTree(DataFormat="row");
floatingBaseBody = rigidBody("floatingBase");
floatingBaseBody.Joint = rigidBodyJoint("j1","floating");

右ボディを固定ベースの剛体ツリーに追加します。これで、剛体と固定ベースがフローティング ジョイントで結合され、"xyz" 軸内および軸に沿った自由な並進と回転が可能になります。

addBody(rbt,floatingBaseBody,rbt.BaseName);

ABB IRB 120 ロボット アームの剛体ツリー モデルを読み込み、読み込まれた剛体ツリーをフローティング ベースの剛体ツリーに追加します。名前の競合を避けるために、フローティング ベースの剛体ツリーの BaseName プロパティの名前を 'world' に変更します。この名前の競合は、両方の剛体ツリーが既定のベース名 'base_link' を使用しているために発生します。

abbirb = loadrobot("abbIrb120",DataFormat="row");
rbt.BaseName = 'world';
addSubtree(rbt,"floatingBase",abbirb,ReplaceBase=false);

剛体ツリーが空間内で自由に並進および回転できることを示すために、固定ベースの座標系における [0 pi/2 pi/3] の方向で "xyz" 座標 [-1.1, 0.2, 0.3] にあるロボット アームのベースを可視化します。

baseOrientation = eul2quat([0 pi/3 pi/3]); % ZYX Euler rotation order
basePosition = [-1.1 0.2 0.3];
floatingRBTConfig = [baseOrientation,basePosition,homeConfiguration(abbirb)]
floatingRBTConfig = 1×13

    0.7500    0.4330    0.4330   -0.2500   -1.1000    0.2000    0.3000         0         0         0         0         0         0

show(rbt,floatingRBTConfig);
axis equal
title(["Robot Joint Configuration With Base", "at Desired Position and Orientation"])

Figure contains an axes object. The axes object with title Robot Joint Configuration With Base at Desired Position and Orientation, xlabel X, ylabel Y contains 28 objects of type patch, line. These objects represent world, floatingBase, base_link, base, link_1, link_2, link_3, link_4, link_5, link_6, tool0, base_link_mesh, link_1_mesh, link_2_mesh, link_3_mesh, link_4_mesh, link_5_mesh, link_6_mesh.

このフローティングベースのロボットを順運動学やダイナミクスなどの用途で使用できるようになりました。前述のように、inverseKinematics を使用するかそのモーション プランニングを行う場合、この方法でフローティングベースのロボットをモデル化することはできません。これを試行すると、逆運動学関数でエラーが発生します。逆運動学およびモーション プランニングでフローティング ロボットをモデル化するには、Inverse Kinematics for Robots with Floating Baseを参照してください。

制限

これらの制限と、これらのオブジェクト、関数、およびブロックで使用するためにフローティングベースのロボットをモデル化する方法の詳細については、Inverse Kinematics for Robots with Floating Baseを参照してください。

参照

[1] Craig, John J. Introduction to Robotics: Mechanics and Control. Reading, MA: Addison-Wesley, 1989.

[2] Siciliano, Bruno. Robotics: Modelling, Planning and Control. London: Springer, 2009.

拡張機能

C/C++ コード生成
MATLAB® Coder™ を使用して C および C++ コードを生成します。

バージョン履歴

R2016b で導入

すべて展開する