本教程介紹瞭如何通過編輯SDF文件來製作簡單的兩杆式夾持器。
想要以圖形化界面的方式編輯模型,請參見“ 模型編輯器” 教程。
文章目錄
一、編寫世界文件
1、爲.world文件創建一個目錄
mkdir ~/simple_gripper_tutorial
cd ~/simple_gripper_tutorial
2、創建一個世界文件
gedit ~/simple_gripper_tutorial/gripper.world
將以下SDF標準內容複製到clipper.world
<?xml version="1.0"?>
<sdf version="1.4">
<world name="default">
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://my_gripper</uri>
</include>
</world>
</sdf>
注意這時候不要啓動gazebo,因爲我們的模型還沒創建
二、 編寫模型文件
1、創建模型保存目錄
在〜/ .gazebo
中創建一個模型目錄。這是我們放置模型文件的位置
mkdir -p ~/.gazebo/models/my_gripper
cd ~/.gazebo/models/my_gripper
2、創建一個model.config文件:
gedit model.config
並複製以下內容:
<?xml version="1.0"?>
<model>
<name>My Gripper</name>
<version>1.0</version>
<sdf version='1.4'>simple_gripper.sdf</sdf>
<author>
<name>My Name</name>
<email>[email protected]</email>
</author>
<description>
My awesome robot.
</description>
</model>
2、創建一個 simple_gripper.sdf
文件
填入以下代碼
<?xml version="1.0"?>
<sdf version="1.4">
<model name="simple_gripper">
<link name="riser">
<pose>-0.15 0.0 0.5 0 0 0</pose>
<inertial>
<pose>0 0 -0.5 0 0 0</pose>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.2 0.2 1.0</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 0.2 1.0</size>
</box>
</geometry>
<material>
<script>Gazebo/Purple</script>
</material>
</visual>
</link>
<link name="palm">
<pose>0.0 0.0 0.05 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.5</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Red</script>
</material>
</visual>
</link>
<link name="left_finger">
<pose>0.1 0.2 0.05 0 0 -0.78539</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Blue</script>
</material>
</visual>
</link>
<link name="left_finger_tip">
<pose>0.336 0.3 0.05 0 0 1.5707</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Blue</script>
</material>
</visual>
</link>
<link name="right_finger">
<pose>0.1 -0.2 0.05 0 0 .78539</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.3 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Green</script>
</material>
</visual>
</link>
<link name="right_finger_tip">
<pose>0.336 -0.3 0.05 0 0 1.5707</pose>
<inertial>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.2 0.1</size>
</box>
</geometry>
<material>
<script>Gazebo/Green</script>
</material>
</visual>
</link>
<static>true</static>
</model>
</sdf>
<static>true</static>
該標籤意味着,我們當前模型是靜態的,模擬器啓動時鏈接不會移動。
運行.world文件查看當前我們創建的內容。
gazebo ~/simple_gripper_tutorial/gripper.world
沒問題的話應該會看到以下畫面
但是到目前爲止,我們的夾子只有link,尚未創建關節,因此,繼續編輯sdf文件
gedit ~/.gazebo/models/my_gripper/simple_gripper.sdf
複製一下內容到<mldel></model>
中:
<joint name="palm_left_finger" type="revolute">
<pose>0 -0.15 0 0 0 0</pose>
<child>left_finger</child>
<parent>palm</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="left_finger_tip" type="revolute">
<pose>0 0.1 0 0 0 0</pose>
<child>left_finger_tip</child>
<parent>left_finger</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="palm_right_finger" type="revolute">
<pose>0 0.15 0 0 0 0</pose>
<child>right_finger</child>
<parent>palm</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="right_finger_tip" type="revolute">
<pose>0 0.1 0 0 0 0</pose>
<child>right_finger_tip</child>
<parent>right_finger</parent>
<axis>
<limit>
<lower>-0.4</lower>
<upper>0.4</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="palm_riser" type="prismatic">
<child>palm</child>
<parent>riser</parent>
<axis>
<limit>
<lower>0</lower>
<upper>0.9</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
將模型改回動態的
...
<static>false</static>
...
重新啓動gazebo:
gazebo ~/simple_gripper_tutorial/gripper.world
右鍵單擊模型,然後選擇“view>joints
”和“view->Wireframe
”。新創建的關節有以下顯示效果:
您還可以使用右邊的“關節控制”部件控制每個關節上的力。
單擊抓爪模型。然後通過單擊GUI右側的垂直手柄並將其拖動到左側來展開此小部件。
該小部件顯示一個滑塊列表,每個關節一個。選擇“力”選項卡,然後使用滑塊將力施加到每個關節,您應該會看到抓爪移動。例如,將力設置palm_riser爲10(牛頓),您應該看到類似以下內容: