本教程介绍了如何通过编辑SDF文件来制作简单的两杆式夹持器。
想要以图形化界面的方式编辑模型,请参见“ 模型编辑器” 教程。
文章目录
- 一、编写世界文件
-
-
- 1、为.world文件创建一个目录
- 2、创建一个世界文件
-
- 二、 编写模型文件
-
-
- 1、创建模型保存目录
- 2、创建一个model.config文件:
- 2、创建一个 `simple_gripper.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>me@my.email</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(牛顿),您应该看到类似以下内容:
评论(0)
您还未登录,请登录后发表或查看评论