本教程将会介绍如何制作一个简单的二栏捏抓手。
mkdir ~/simple_gripper_tutorial; cd ~/simple_gripper_tutorial
gedit ~/simple_gripper_tutorial/gripper.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>
mkdir -p ~/.gazebo/models/my_gripper
5.生成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>
<?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>gedit ~/.gazebo/models/my_gripper/simple_gripper.sdf </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>
gazebo ~/simple_gripper_tutorial/gripper.world
你将看到如上图所示。
1.一旦我们对链接的布局满意,我们可以通过复制以下代码到simple_gripper.sdf中的</model>行前来添加关节。
gedit ~/.gazebo/models/my_gripper/simple_gripper.sdf
<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 ~/simple_gripper_tutorial/gripper.world
1.你也可以通过用Joint Control widget来控制每个关节的力点击夹具模型,之后点击用户界面的右侧垂直手柄,拖拽到左边来扩大这个插件。这个插件显示滑动条列表。选择Force tab,并且用滑动条来对每个关节施加力,你将会看到抓手移动。例如,设置palm_riser为10,你将看到如下:
可选:
添加一个小盒子或者圆筒到world,并且用夹具定位。尝试用用户界面的joint control 来夹起对象。
你需要调整合理的惯性对象。