Skip to content

Commit

Permalink
Add Link8 and GripperPart as Link10
Browse files Browse the repository at this point in the history
  • Loading branch information
asukiaaa committed Feb 3, 2019
1 parent a735297 commit c3e13c4
Show file tree
Hide file tree
Showing 5 changed files with 33 additions and 5 deletions.
2 changes: 1 addition & 1 deletion pro_moveit_config/config/fake_controllers.yaml
Expand Up @@ -4,4 +4,4 @@ controller_list:
- Joint1
- Joint2
- Joint3
- Joint8
- Joint10
4 changes: 4 additions & 0 deletions pro_moveit_config/config/swiftpro.srdf
Expand Up @@ -15,16 +15,19 @@
<link name="Link2" />
<link name="Link3" />
<link name="Link8" />
<link name="Link10" />
<joint name="Joint1" />
<joint name="Joint2" />
<joint name="Joint3" />
<joint name="Joint10" />
<chain base_link="Base" tip_link="Link3" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="arm">
<joint name="Joint1" value="0" />
<joint name="Joint2" value="0" />
<joint name="Joint3" value="0" />
<joint name="Joint10" value="0" />
</group_state>
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="Joint8" />
Expand Down Expand Up @@ -73,4 +76,5 @@
<disable_collisions link1="Link7" link2="Link8" reason="User" />
<disable_collisions link1="Link7" link2="Link9" reason="Never" />
<disable_collisions link1="Link8" link2="Link9" reason="Adjacent" />
<disable_collisions link1="Link8" link2="Link10" reason="Adjacent" />
</robot>
Binary file added swiftpro/urdf/pro_links/GripperPart.STL
Binary file not shown.
Binary file added swiftpro/urdf/pro_links/Link8.STL
Binary file not shown.
32 changes: 28 additions & 4 deletions swiftpro/urdf/pro_model.xacro
Expand Up @@ -101,8 +101,6 @@
</joint>




<link name="Link4">
<inertial>
<origin xyz="-0.00235 0.013618 0.015458" rpy="0 0 0"/>
Expand Down Expand Up @@ -215,12 +213,12 @@
<inertial>
<origin xyz="0.027288 0.001085 -0.007344" rpy="0 0 0"/>
<mass value="0.012"/>
<inertia ixx="0.000002184" ixy="0.000000020" ixz="-0.000000207"
<inertia ixx="0.000002184" ixy="0.000000020" ixz="-0.000000207"
iyy="0.000002992" iyz="0.000000371" izz="0.000001832"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/Gripper.STL"/>
<mesh filename="package://swiftpro/urdf/pro_links/Link8.STL"/>
</geometry>
<origin xyz = "-0.17201 0 -0.24651" rpy = "0 0 0" />
<material name = "">
Expand Down Expand Up @@ -265,4 +263,30 @@
</joint>


<link name="Link10">
<inertial>
<origin xyz="0.027288 0.001085 -0.007344" rpy="0 0 0"/>
<mass value="0.012"/>
<inertia ixx="0.000002184" ixy="0.000000020" ixz="-0.000000207"
iyy="0.000002992" iyz="0.000000371" izz="0.000001832"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://swiftpro/urdf/pro_links/GripperPart.STL"/>
</geometry>
<origin xyz = "-0.22201 0 -0.24651" rpy = "0 0 0" />
<material name = "">
<color rgba = "0.3 0.3 0.3 1" />
</material>
</visual>
</link>

<joint name="Joint10" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-3" upper = "3" velocity = "0" />
<parent link="Link8"/>
<child link="Link10"/>
<origin xyz= "0.05 0 0" rpy = " 0 0 0" />
</joint>

</robot>

0 comments on commit c3e13c4

Please sign in to comment.